From 4cac9d2b951e7352cba89716a9c1fca5dbc91403 Mon Sep 17 00:00:00 2001 From: Marcin Anforowicz Date: Thu, 12 Sep 2024 15:02:05 -0700 Subject: [PATCH] Add OpenCyphal Node (#3) * Added canard components * Added OpenCyphal node. * Added collapsible descriptions to settings in webpage. * Split github workflow into build and release. * Added some simple performance optimizations * Removed *.dsdl files, and added update script to fetch and compile them. * Removed unneeded reg DSDL headers. * Updated status report wording. * Changed cyphal node to keep trying sending heartbeat --------- Co-authored-by: Marcin Anforowicz --- .github/workflows/build.yml | 53 +- .github/workflows/release.yml | 42 + components/esp_canard/CMakeLists.txt | 5 + components/esp_canard/canard.c | 1310 +++++++++++++++++ components/esp_canard/include/_canard_cavl.h | 337 +++++ components/esp_canard/include/canard.h | 714 +++++++++ components/esp_nunavut/CMakeLists.txt | 3 + .../nunavut/nunavut/support/serialization.h | 585 ++++++++ .../nunavut/uavcan/_register/Access_1_0.h | 492 +++++++ .../nunavut/uavcan/_register/List_1_0.h | 357 +++++ .../nunavut/uavcan/_register/Name_1_0.h | 242 +++ .../nunavut/uavcan/_register/Value_1_0.h | 878 +++++++++++ .../nunavut/uavcan/diagnostic/Record_1_0.h | 315 ++++ .../nunavut/uavcan/diagnostic/Record_1_1.h | 306 ++++ .../nunavut/uavcan/diagnostic/Severity_1_0.h | 235 +++ .../nunavut/uavcan/file/Error_1_0.h | 234 +++ .../nunavut/uavcan/file/GetInfo_0_1.h | 505 +++++++ .../nunavut/uavcan/file/GetInfo_0_2.h | 496 +++++++ .../nunavut/uavcan/file/List_0_1.h | 425 ++++++ .../nunavut/uavcan/file/List_0_2.h | 416 ++++++ .../nunavut/uavcan/file/Modify_1_0.h | 475 ++++++ .../nunavut/uavcan/file/Modify_1_1.h | 466 ++++++ .../nunavut/uavcan/file/Path_1_0.h | 257 ++++ .../nunavut/uavcan/file/Path_2_0.h | 248 ++++ .../nunavut/uavcan/file/Read_1_0.h | 452 ++++++ .../nunavut/uavcan/file/Read_1_1.h | 430 ++++++ .../nunavut/uavcan/file/Write_1_0.h | 455 ++++++ .../nunavut/uavcan/file/Write_1_1.h | 430 ++++++ .../internet/udp/HandleIncomingPacket_0_1.h | 369 +++++ .../internet/udp/HandleIncomingPacket_0_2.h | 360 +++++ .../uavcan/internet/udp/OutgoingPacket_0_1.h | 387 +++++ .../uavcan/internet/udp/OutgoingPacket_0_2.h | 378 +++++ .../metatransport/can/ArbitrationID_0_1.h | 306 ++++ .../metatransport/can/BaseArbitrationID_0_1.h | 213 +++ .../metatransport/can/DataClassic_0_1.h | 268 ++++ .../uavcan/metatransport/can/DataFD_0_1.h | 268 ++++ .../uavcan/metatransport/can/Error_0_1.h | 196 +++ .../can/ExtendedArbitrationID_0_1.h | 213 +++ .../uavcan/metatransport/can/Frame_0_1.h | 260 ++++ .../uavcan/metatransport/can/Frame_0_2.h | 394 +++++ .../metatransport/can/Manifestation_0_1.h | 403 +++++ .../uavcan/metatransport/can/RTR_0_1.h | 214 +++ .../metatransport/ethernet/EtherType_0_1.h | 213 +++ .../uavcan/metatransport/ethernet/Frame_0_1.h | 339 +++++ .../metatransport/serial/Fragment_0_1.h | 277 ++++ .../metatransport/serial/Fragment_0_2.h | 242 +++ .../uavcan/metatransport/udp/Endpoint_0_1.h | 282 ++++ .../uavcan/metatransport/udp/Frame_0_1.h | 357 +++++ .../nunavut/uavcan/node/ExecuteCommand_1_0.h | 450 ++++++ .../nunavut/uavcan/node/ExecuteCommand_1_1.h | 450 ++++++ .../nunavut/uavcan/node/ExecuteCommand_1_2.h | 453 ++++++ .../nunavut/uavcan/node/ExecuteCommand_1_3.h | 497 +++++++ .../nunavut/uavcan/node/GetInfo_1_0.h | 596 ++++++++ .../uavcan/node/GetTransportStatistics_0_1.h | 395 +++++ .../nunavut/uavcan/node/Health_1_0.h | 223 +++ .../nunavut/uavcan/node/Heartbeat_1_0.h | 303 ++++ .../esp_nunavut/nunavut/uavcan/node/ID_1_0.h | 204 +++ .../nunavut/uavcan/node/IOStatistics_0_1.h | 231 +++ .../nunavut/uavcan/node/Mode_1_0.h | 223 +++ .../nunavut/uavcan/node/Version_1_0.h | 225 +++ .../nunavut/uavcan/node/port/ID_1_0.h | 306 ++++ .../nunavut/uavcan/node/port/List_0_1.h | 404 +++++ .../nunavut/uavcan/node/port/List_1_0.h | 395 +++++ .../uavcan/node/port/ServiceIDList_0_1.h | 219 +++ .../uavcan/node/port/ServiceIDList_1_0.h | 210 +++ .../nunavut/uavcan/node/port/ServiceID_1_0.h | 211 +++ .../uavcan/node/port/SubjectIDList_0_1.h | 388 +++++ .../uavcan/node/port/SubjectIDList_1_0.h | 379 +++++ .../nunavut/uavcan/node/port/SubjectID_1_0.h | 211 +++ .../uavcan/pnp/NodeIDAllocationData_1_0.h | 275 ++++ .../uavcan/pnp/NodeIDAllocationData_2_0.h | 248 ++++ .../uavcan/pnp/cluster/AppendEntries_1_0.h | 487 ++++++ .../uavcan/pnp/cluster/Discovery_1_0.h | 300 ++++ .../nunavut/uavcan/pnp/cluster/Entry_1_0.h | 273 ++++ .../uavcan/pnp/cluster/RequestVote_1_0.h | 394 +++++ .../nunavut/uavcan/primitive/Empty_1_0.h | 167 +++ .../nunavut/uavcan/primitive/String_1_0.h | 239 +++ .../uavcan/primitive/Unstructured_1_0.h | 239 +++ .../nunavut/uavcan/primitive/array/Bit_1_0.h | 227 +++ .../uavcan/primitive/array/Integer16_1_0.h | 239 +++ .../uavcan/primitive/array/Integer32_1_0.h | 239 +++ .../uavcan/primitive/array/Integer64_1_0.h | 239 +++ .../uavcan/primitive/array/Integer8_1_0.h | 232 +++ .../uavcan/primitive/array/Natural16_1_0.h | 239 +++ .../uavcan/primitive/array/Natural32_1_0.h | 239 +++ .../uavcan/primitive/array/Natural64_1_0.h | 239 +++ .../uavcan/primitive/array/Natural8_1_0.h | 239 +++ .../uavcan/primitive/array/Real16_1_0.h | 249 ++++ .../uavcan/primitive/array/Real32_1_0.h | 239 +++ .../uavcan/primitive/array/Real64_1_0.h | 239 +++ .../nunavut/uavcan/primitive/scalar/Bit_1_0.h | 206 +++ .../uavcan/primitive/scalar/Integer16_1_0.h | 204 +++ .../uavcan/primitive/scalar/Integer32_1_0.h | 204 +++ .../uavcan/primitive/scalar/Integer64_1_0.h | 204 +++ .../uavcan/primitive/scalar/Integer8_1_0.h | 200 +++ .../uavcan/primitive/scalar/Natural16_1_0.h | 204 +++ .../uavcan/primitive/scalar/Natural32_1_0.h | 204 +++ .../uavcan/primitive/scalar/Natural64_1_0.h | 204 +++ .../uavcan/primitive/scalar/Natural8_1_0.h | 207 +++ .../uavcan/primitive/scalar/Real16_1_0.h | 214 +++ .../uavcan/primitive/scalar/Real32_1_0.h | 204 +++ .../uavcan/primitive/scalar/Real64_1_0.h | 204 +++ .../si/sample/acceleration/Scalar_1_0.h | 230 +++ .../si/sample/acceleration/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/angle/Quaternion_1_0.h | 244 +++ .../uavcan/si/sample/angle/Scalar_1_0.h | 230 +++ .../sample/angular_acceleration/Scalar_1_0.h | 230 +++ .../sample/angular_acceleration/Vector3_1_0.h | 244 +++ .../si/sample/angular_velocity/Scalar_1_0.h | 230 +++ .../si/sample/angular_velocity/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/duration/Scalar_1_0.h | 230 +++ .../si/sample/duration/WideScalar_1_0.h | 230 +++ .../si/sample/electric_charge/Scalar_1_0.h | 230 +++ .../si/sample/electric_current/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/energy/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/force/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/force/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/frequency/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/length/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/length/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/length/WideScalar_1_0.h | 230 +++ .../uavcan/si/sample/length/WideVector3_1_0.h | 244 +++ .../uavcan/si/sample/luminance/Scalar_1_0.h | 230 +++ .../magnetic_field_strength/Scalar_1_0.h | 239 +++ .../magnetic_field_strength/Scalar_1_1.h | 230 +++ .../magnetic_field_strength/Vector3_1_0.h | 253 ++++ .../magnetic_field_strength/Vector3_1_1.h | 244 +++ .../sample/magnetic_flux_density/Scalar_1_0.h | 230 +++ .../magnetic_flux_density/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/mass/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/power/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/pressure/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/temperature/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/torque/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/torque/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/velocity/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/velocity/Vector3_1_0.h | 244 +++ .../uavcan/si/sample/voltage/Scalar_1_0.h | 230 +++ .../uavcan/si/sample/volume/Scalar_1_0.h | 230 +++ .../sample/volumetric_flow_rate/Scalar_1_0.h | 230 +++ .../uavcan/si/unit/acceleration/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/acceleration/Vector3_1_0.h | 218 +++ .../uavcan/si/unit/angle/Quaternion_1_0.h | 218 +++ .../nunavut/uavcan/si/unit/angle/Scalar_1_0.h | 204 +++ .../si/unit/angular_acceleration/Scalar_1_0.h | 204 +++ .../unit/angular_acceleration/Vector3_1_0.h | 218 +++ .../si/unit/angular_velocity/Scalar_1_0.h | 204 +++ .../si/unit/angular_velocity/Vector3_1_0.h | 218 +++ .../uavcan/si/unit/duration/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/duration/WideScalar_1_0.h | 204 +++ .../si/unit/electric_charge/Scalar_1_0.h | 204 +++ .../si/unit/electric_current/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/energy/Scalar_1_0.h | 204 +++ .../nunavut/uavcan/si/unit/force/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/force/Vector3_1_0.h | 218 +++ .../uavcan/si/unit/frequency/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/length/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/length/Vector3_1_0.h | 218 +++ .../uavcan/si/unit/length/WideScalar_1_0.h | 204 +++ .../uavcan/si/unit/length/WideVector3_1_0.h | 218 +++ .../uavcan/si/unit/luminance/Scalar_1_0.h | 204 +++ .../unit/magnetic_field_strength/Scalar_1_0.h | 213 +++ .../unit/magnetic_field_strength/Scalar_1_1.h | 204 +++ .../magnetic_field_strength/Vector3_1_0.h | 227 +++ .../magnetic_field_strength/Vector3_1_1.h | 218 +++ .../unit/magnetic_flux_density/Scalar_1_0.h | 204 +++ .../unit/magnetic_flux_density/Vector3_1_0.h | 218 +++ .../nunavut/uavcan/si/unit/mass/Scalar_1_0.h | 204 +++ .../nunavut/uavcan/si/unit/power/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/pressure/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/temperature/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/torque/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/torque/Vector3_1_0.h | 218 +++ .../uavcan/si/unit/velocity/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/velocity/Vector3_1_0.h | 218 +++ .../uavcan/si/unit/voltage/Scalar_1_0.h | 204 +++ .../uavcan/si/unit/volume/Scalar_1_0.h | 204 +++ .../si/unit/volumetric_flow_rate/Scalar_1_0.h | 204 +++ .../time/GetSynchronizationMasterInfo_0_1.h | 384 +++++ .../nunavut/uavcan/time/Synchronization_1_0.h | 209 +++ .../uavcan/time/SynchronizedTimestamp_1_0.h | 206 +++ .../nunavut/uavcan/time/TAIInfo_0_1.h | 214 +++ .../nunavut/uavcan/time/TimeSystem_0_1.h | 215 +++ components/esp_nunavut/recompile_dsdl.sh | 31 + components/esp_o1heap/CMakeLists.txt | 5 + components/esp_o1heap/include/o1heap.h | 122 ++ components/esp_o1heap/o1heap.c | 497 +++++++ main/CMakeLists.txt | 4 + main/can_listener.c | 213 +++ main/can_listener.h | 46 + main/cyphal_node.c | 240 +++ main/cyphal_node.h | 20 + main/discovery_beacon.c | 20 +- main/driver_setup.c | 13 +- main/frame_io.c | 3 +- main/frame_io.h | 7 +- main/http_server.c | 25 + main/main.c | 21 +- main/persistent_settings.c | 10 +- main/persistent_settings.h | 8 + main/socketcand_server.c | 433 +++--- main/socketcand_server.h | 12 +- main/socketcand_translate.c | 43 +- main/socketcand_translate.h | 20 +- main/status_report.c | 151 +- main/status_report.h | 4 +- main/website/index.html | 58 +- main/website/script.js | 5 +- sdkconfig.defaults | 6 + 209 files changed, 51778 insertions(+), 346 deletions(-) create mode 100644 .github/workflows/release.yml create mode 100644 components/esp_canard/CMakeLists.txt create mode 100644 components/esp_canard/canard.c create mode 100644 components/esp_canard/include/_canard_cavl.h create mode 100644 components/esp_canard/include/canard.h create mode 100644 components/esp_nunavut/CMakeLists.txt create mode 100644 components/esp_nunavut/nunavut/nunavut/support/serialization.h create mode 100644 components/esp_nunavut/nunavut/uavcan/_register/Access_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/_register/List_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/_register/Name_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/_register/Value_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/diagnostic/Severity_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Error_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/List_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/List_0_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Modify_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Modify_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Path_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Path_2_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Read_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Read_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Write_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/file/Write_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/ArbitrationID_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/BaseArbitrationID_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/DataClassic_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/DataFD_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/Error_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/ExtendedArbitrationID_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/Manifestation_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/can/RTR_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/EtherType_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/Frame_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/udp/Endpoint_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/metatransport/udp/Frame_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_2.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_3.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/GetInfo_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/GetTransportStatistics_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/Health_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/Heartbeat_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/ID_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/IOStatistics_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/Mode_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/Version_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/ID_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/List_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/List_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/ServiceID_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/node/port/SubjectID_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_2_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/pnp/cluster/AppendEntries_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/pnp/cluster/Discovery_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/pnp/cluster/Entry_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/pnp/cluster/RequestVote_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/Empty_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/String_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/Unstructured_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Bit_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Integer16_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Integer32_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Integer64_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Integer8_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Natural16_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Natural32_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Natural64_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Natural8_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Real16_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Real32_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/array/Real64_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Bit_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer16_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer32_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer64_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer8_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural16_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural32_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural64_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural8_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real16_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real32_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real64_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/angle/Quaternion_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/angle/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/duration/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/duration/WideScalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/electric_charge/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/electric_current/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/energy/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/force/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/force/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/frequency/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/length/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/length/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/length/WideScalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/length/WideVector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/luminance/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/mass/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/power/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/pressure/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/temperature/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/torque/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/torque/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/voltage/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/volume/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/sample/volumetric_flow_rate/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/angle/Quaternion_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/angle/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/duration/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/duration/WideScalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/electric_charge/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/electric_current/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/energy/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/force/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/force/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/frequency/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/length/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/length/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/length/WideScalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/length/WideVector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/luminance/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/mass/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/power/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/pressure/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/temperature/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/torque/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/torque/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Vector3_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/voltage/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/volume/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/si/unit/volumetric_flow_rate/Scalar_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/time/GetSynchronizationMasterInfo_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/time/Synchronization_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/time/SynchronizedTimestamp_1_0.h create mode 100644 components/esp_nunavut/nunavut/uavcan/time/TAIInfo_0_1.h create mode 100644 components/esp_nunavut/nunavut/uavcan/time/TimeSystem_0_1.h create mode 100755 components/esp_nunavut/recompile_dsdl.sh create mode 100644 components/esp_o1heap/CMakeLists.txt create mode 100644 components/esp_o1heap/include/o1heap.h create mode 100644 components/esp_o1heap/o1heap.c create mode 100644 main/can_listener.c create mode 100644 main/can_listener.h create mode 100644 main/cyphal_node.c create mode 100644 main/cyphal_node.h diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index ee971bb..04f9b75 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -1,43 +1,36 @@ name: Build # Run this action during every push and pull request. -# 'workflow_call' lets this action be called by other actions. -on: [push, pull_request] +on: + push: + branches: + - "**" + pull_request: # List of jobs that this action will run. jobs: # This job will build the project on ubuntu # using esp-idf-ci-action. build: - runs-on: ubuntu-latest steps: - - name: Checkout repo - uses: actions/checkout@v4 - with: - submodules: 'recursive' - - # Build the project using - # esp-idf-ci-action. - - name: Build - uses: espressif/esp-idf-ci-action@v1 - with: - esp_idf_version: latest - target: esp32 - path: '/' - command: | - idf.py build && - cd build && - mkdir merged && - esptool.py --chip esp32 merge_bin -o merged/esp32_socketcand_adapter.bin @flash_args && - cd ../ - - # If a tag was pushed, publish a release - # with the binaries produced by the previous step. - - name: Release - uses: softprops/action-gh-release@v2 - if: startsWith(github.ref, 'refs/tags/') - with: - files: build/merged/esp32_socketcand_adapter.bin + - name: Checkout repo + uses: actions/checkout@v4 + with: + submodules: "recursive" + # Build the project using + # esp-idf-ci-action. + - name: Test build + uses: espressif/esp-idf-ci-action@v1 + with: + esp_idf_version: latest + target: esp32 + path: "/" + command: | + idf.py build && + cd build && + mkdir merged && + esptool.py --chip esp32 merge_bin -o merged/esp32_socketcand_adapter.bin @flash_args && + cd ../ diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml new file mode 100644 index 0000000..ca635cf --- /dev/null +++ b/.github/workflows/release.yml @@ -0,0 +1,42 @@ +name: Release + +# Run this action during every tag push. +on: + push: + tags: + - "**" + +# List of jobs that this action will run. +jobs: + # This job will build the project on ubuntu + # using esp-idf-ci-action. + build: + runs-on: ubuntu-latest + + steps: + - name: Checkout repo + uses: actions/checkout@v4 + with: + submodules: "recursive" + + # Build the project using + # esp-idf-ci-action. + - name: Build Release + uses: espressif/esp-idf-ci-action@v1 + with: + esp_idf_version: v5.3.1 + target: esp32 + path: "/" + command: | + idf.py build && + cd build && + mkdir merged && + esptool.py --chip esp32 merge_bin -o merged/esp32_socketcand_adapter.bin @flash_args && + cd ../ + + # If a tag was pushed, publish a release + # with the binaries produced by the previous step. + - name: Publish Release + uses: softprops/action-gh-release@v2 + with: + files: build/merged/esp32_socketcand_adapter.bin diff --git a/components/esp_canard/CMakeLists.txt b/components/esp_canard/CMakeLists.txt new file mode 100644 index 0000000..f0ad233 --- /dev/null +++ b/components/esp_canard/CMakeLists.txt @@ -0,0 +1,5 @@ +idf_component_register( + SRCS + "canard.c" + INCLUDE_DIRS "include" +) diff --git a/components/esp_canard/canard.c b/components/esp_canard/canard.c new file mode 100644 index 0000000..ec6e6d3 --- /dev/null +++ b/components/esp_canard/canard.c @@ -0,0 +1,1310 @@ +/// This software is distributed under the terms of the MIT License. +/// Copyright (c) 2016 OpenCyphal. +/// Author: Pavel Kirienko + +#include "canard.h" +#include + +// --------------------------------------------- BUILD CONFIGURATION --------------------------------------------- + +/// Define this macro to include build configuration header. +/// Usage example with CMake: "-DCANARD_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/my_canard_config.h\"" +#ifdef CANARD_CONFIG_HEADER +# include CANARD_CONFIG_HEADER +#endif + +/// By default, this macro resolves to the standard assert(). The user can redefine this if necessary. +/// To disable assertion checks completely, make it expand into `(void)(0)`. +#ifndef CANARD_ASSERT +// Intentional violation of MISRA: inclusion not at the top of the file to eliminate unnecessary dependency on assert.h. +# include // NOSONAR +// Intentional violation of MISRA: assertion macro cannot be replaced with a function definition. +# define CANARD_ASSERT(x) assert(x) // NOSONAR +#endif + +/// Define CANARD_CRC_TABLE=0 to use slow but ROM-efficient transfer-CRC computation algorithm. +/// Doing so is expected to save ca. 500 bytes of ROM and increase the cost of RX/TX transfer processing by ~half. +#ifndef CANARD_CRC_TABLE +# define CANARD_CRC_TABLE 1 +#endif + +/// This macro is needed for testing and for library development. +#ifndef CANARD_PRIVATE +# define CANARD_PRIVATE static inline +#endif + +#if !defined(__STDC_VERSION__) || (__STDC_VERSION__ < 199901L) +# error "Unsupported language: ISO C99 or a newer version is required." +#endif + +// --------------------------------------------- INTERNAL INCLUDES ---------------------------------------------- +// The internal includes are placed here after the config header is included and CANARD_ASSERT is defined. + +#include "_canard_cavl.h" + +// --------------------------------------------- COMMON DEFINITIONS --------------------------------------------- + +#define BITS_PER_BYTE 8U +#define BYTE_MAX 0xFFU + +#define CAN_EXT_ID_MASK ((UINT32_C(1) << 29U) - 1U) + +#define MFT_NON_LAST_FRAME_PAYLOAD_MIN 7U + +#define PADDING_BYTE_VALUE 0U + +#define OFFSET_PRIORITY 26U +#define OFFSET_SUBJECT_ID 8U +#define OFFSET_SERVICE_ID 14U +#define OFFSET_DST_NODE_ID 7U + +#define FLAG_SERVICE_NOT_MESSAGE (UINT32_C(1) << 25U) +#define FLAG_ANONYMOUS_MESSAGE (UINT32_C(1) << 24U) +#define FLAG_REQUEST_NOT_RESPONSE (UINT32_C(1) << 24U) +#define FLAG_RESERVED_23 (UINT32_C(1) << 23U) +#define FLAG_RESERVED_07 (UINT32_C(1) << 7U) + +#define TAIL_START_OF_TRANSFER 128U +#define TAIL_END_OF_TRANSFER 64U +#define TAIL_TOGGLE 32U + +#define INITIAL_TOGGLE_STATE true + +/// Used for inserting new items into AVL trees. +CANARD_PRIVATE CanardTreeNode* avlTrivialFactory(void* const user_reference) +{ + return (CanardTreeNode*) user_reference; +} + +// --------------------------------------------- TRANSFER CRC --------------------------------------------- + +typedef uint16_t TransferCRC; + +#define CRC_INITIAL 0xFFFFU +#define CRC_RESIDUE 0x0000U +#define CRC_SIZE_BYTES 2U + +#if (CANARD_CRC_TABLE != 0) +static const uint16_t CRCTable[256] = { + 0x0000U, 0x1021U, 0x2042U, 0x3063U, 0x4084U, 0x50A5U, 0x60C6U, 0x70E7U, 0x8108U, 0x9129U, 0xA14AU, 0xB16BU, 0xC18CU, + 0xD1ADU, 0xE1CEU, 0xF1EFU, 0x1231U, 0x0210U, 0x3273U, 0x2252U, 0x52B5U, 0x4294U, 0x72F7U, 0x62D6U, 0x9339U, 0x8318U, + 0xB37BU, 0xA35AU, 0xD3BDU, 0xC39CU, 0xF3FFU, 0xE3DEU, 0x2462U, 0x3443U, 0x0420U, 0x1401U, 0x64E6U, 0x74C7U, 0x44A4U, + 0x5485U, 0xA56AU, 0xB54BU, 0x8528U, 0x9509U, 0xE5EEU, 0xF5CFU, 0xC5ACU, 0xD58DU, 0x3653U, 0x2672U, 0x1611U, 0x0630U, + 0x76D7U, 0x66F6U, 0x5695U, 0x46B4U, 0xB75BU, 0xA77AU, 0x9719U, 0x8738U, 0xF7DFU, 0xE7FEU, 0xD79DU, 0xC7BCU, 0x48C4U, + 0x58E5U, 0x6886U, 0x78A7U, 0x0840U, 0x1861U, 0x2802U, 0x3823U, 0xC9CCU, 0xD9EDU, 0xE98EU, 0xF9AFU, 0x8948U, 0x9969U, + 0xA90AU, 0xB92BU, 0x5AF5U, 0x4AD4U, 0x7AB7U, 0x6A96U, 0x1A71U, 0x0A50U, 0x3A33U, 0x2A12U, 0xDBFDU, 0xCBDCU, 0xFBBFU, + 0xEB9EU, 0x9B79U, 0x8B58U, 0xBB3BU, 0xAB1AU, 0x6CA6U, 0x7C87U, 0x4CE4U, 0x5CC5U, 0x2C22U, 0x3C03U, 0x0C60U, 0x1C41U, + 0xEDAEU, 0xFD8FU, 0xCDECU, 0xDDCDU, 0xAD2AU, 0xBD0BU, 0x8D68U, 0x9D49U, 0x7E97U, 0x6EB6U, 0x5ED5U, 0x4EF4U, 0x3E13U, + 0x2E32U, 0x1E51U, 0x0E70U, 0xFF9FU, 0xEFBEU, 0xDFDDU, 0xCFFCU, 0xBF1BU, 0xAF3AU, 0x9F59U, 0x8F78U, 0x9188U, 0x81A9U, + 0xB1CAU, 0xA1EBU, 0xD10CU, 0xC12DU, 0xF14EU, 0xE16FU, 0x1080U, 0x00A1U, 0x30C2U, 0x20E3U, 0x5004U, 0x4025U, 0x7046U, + 0x6067U, 0x83B9U, 0x9398U, 0xA3FBU, 0xB3DAU, 0xC33DU, 0xD31CU, 0xE37FU, 0xF35EU, 0x02B1U, 0x1290U, 0x22F3U, 0x32D2U, + 0x4235U, 0x5214U, 0x6277U, 0x7256U, 0xB5EAU, 0xA5CBU, 0x95A8U, 0x8589U, 0xF56EU, 0xE54FU, 0xD52CU, 0xC50DU, 0x34E2U, + 0x24C3U, 0x14A0U, 0x0481U, 0x7466U, 0x6447U, 0x5424U, 0x4405U, 0xA7DBU, 0xB7FAU, 0x8799U, 0x97B8U, 0xE75FU, 0xF77EU, + 0xC71DU, 0xD73CU, 0x26D3U, 0x36F2U, 0x0691U, 0x16B0U, 0x6657U, 0x7676U, 0x4615U, 0x5634U, 0xD94CU, 0xC96DU, 0xF90EU, + 0xE92FU, 0x99C8U, 0x89E9U, 0xB98AU, 0xA9ABU, 0x5844U, 0x4865U, 0x7806U, 0x6827U, 0x18C0U, 0x08E1U, 0x3882U, 0x28A3U, + 0xCB7DU, 0xDB5CU, 0xEB3FU, 0xFB1EU, 0x8BF9U, 0x9BD8U, 0xABBBU, 0xBB9AU, 0x4A75U, 0x5A54U, 0x6A37U, 0x7A16U, 0x0AF1U, + 0x1AD0U, 0x2AB3U, 0x3A92U, 0xFD2EU, 0xED0FU, 0xDD6CU, 0xCD4DU, 0xBDAAU, 0xAD8BU, 0x9DE8U, 0x8DC9U, 0x7C26U, 0x6C07U, + 0x5C64U, 0x4C45U, 0x3CA2U, 0x2C83U, 0x1CE0U, 0x0CC1U, 0xEF1FU, 0xFF3EU, 0xCF5DU, 0xDF7CU, 0xAF9BU, 0xBFBAU, 0x8FD9U, + 0x9FF8U, 0x6E17U, 0x7E36U, 0x4E55U, 0x5E74U, 0x2E93U, 0x3EB2U, 0x0ED1U, 0x1EF0U, +}; +#endif + +CANARD_PRIVATE TransferCRC crcAddByte(const TransferCRC crc, const uint8_t byte) +{ +#if (CANARD_CRC_TABLE != 0) + return (uint16_t) ((uint16_t) (crc << BITS_PER_BYTE) ^ + CRCTable[(uint16_t) ((uint16_t) (crc >> BITS_PER_BYTE) ^ byte) & BYTE_MAX]); +#else + static const TransferCRC Top = 0x8000U; + static const TransferCRC Poly = 0x1021U; + TransferCRC out = crc ^ (uint16_t) ((uint16_t) (byte) << BITS_PER_BYTE); + // Consider adding a compilation option that replaces this with a CRC table. Adds 512 bytes of ROM. + // Do not fold this into a loop because a size-optimizing compiler won't unroll it degrading the performance. + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + out = (uint16_t) ((uint16_t) (out << 1U) ^ (((out & Top) != 0U) ? Poly : 0U)); + return out; +#endif +} + +CANARD_PRIVATE TransferCRC crcAdd(const TransferCRC crc, const size_t size, const void* const data) +{ + CANARD_ASSERT((data != NULL) || (size == 0U)); + TransferCRC out = crc; + const uint8_t* p = (const uint8_t*) data; + for (size_t i = 0; i < size; i++) + { + out = crcAddByte(out, *p); + ++p; + } + return out; +} + +// --------------------------------------------- TRANSMISSION --------------------------------------------- + +/// This is a subclass of CanardTxQueueItem. A pointer to this type can be cast to CanardTxQueueItem safely. +/// This is standard-compliant. The paragraph 6.7.2.1.15 says: +/// A pointer to a structure object, suitably converted, points to its initial member (or if that member is a +/// bit-field, then to the unit in which it resides), and vice versa. There may be unnamed padding within a +/// structure object, but not at its beginning. +typedef struct TxItem +{ + CanardTxQueueItem base; + uint8_t payload_buffer[CANARD_MTU_MAX]; +} TxItem; + +/// Chain of TX frames prepared for insertion into a TX queue. +typedef struct +{ + TxItem* head; + TxItem* tail; + size_t size; +} TxChain; + +CANARD_PRIVATE uint32_t txMakeMessageSessionSpecifier(const CanardPortID subject_id, const CanardNodeID src_node_id) +{ + CANARD_ASSERT(src_node_id <= CANARD_NODE_ID_MAX); + CANARD_ASSERT(subject_id <= CANARD_SUBJECT_ID_MAX); + const uint32_t tmp = subject_id | (CANARD_SUBJECT_ID_MAX + 1) | ((CANARD_SUBJECT_ID_MAX + 1) * 2); + return src_node_id | (tmp << OFFSET_SUBJECT_ID); +} + +CANARD_PRIVATE uint32_t txMakeServiceSessionSpecifier(const CanardPortID service_id, + const bool request_not_response, + const CanardNodeID src_node_id, + const CanardNodeID dst_node_id) +{ + CANARD_ASSERT(src_node_id <= CANARD_NODE_ID_MAX); + CANARD_ASSERT(dst_node_id <= CANARD_NODE_ID_MAX); + CANARD_ASSERT(service_id <= CANARD_SERVICE_ID_MAX); + return src_node_id | (((uint32_t) dst_node_id) << OFFSET_DST_NODE_ID) | // + (((uint32_t) service_id) << OFFSET_SERVICE_ID) | // + (request_not_response ? FLAG_REQUEST_NOT_RESPONSE : 0U) | FLAG_SERVICE_NOT_MESSAGE; +} + +/// This is the transport MTU rounded up to next full DLC minus the tail byte. +CANARD_PRIVATE size_t adjustPresentationLayerMTU(const size_t mtu_bytes) +{ + const size_t max_index = (sizeof(CanardCANLengthToDLC) / sizeof(CanardCANLengthToDLC[0])) - 1U; + size_t mtu = 0U; + if (mtu_bytes < CANARD_MTU_CAN_CLASSIC) + { + mtu = CANARD_MTU_CAN_CLASSIC; + } + else if (mtu_bytes <= max_index) + { + mtu = CanardCANDLCToLength[CanardCANLengthToDLC[mtu_bytes]]; // Round up to nearest valid length. + } + else + { + mtu = CanardCANDLCToLength[CanardCANLengthToDLC[max_index]]; + } + return mtu - 1U; +} + +CANARD_PRIVATE int32_t txMakeCANID(const CanardTransferMetadata* const tr, + const size_t payload_size, + const void* const payload, + const CanardNodeID local_node_id, + const size_t presentation_layer_mtu) +{ + CANARD_ASSERT(tr != NULL); + CANARD_ASSERT(presentation_layer_mtu > 0); + int32_t out = -CANARD_ERROR_INVALID_ARGUMENT; + if ((tr->transfer_kind == CanardTransferKindMessage) && (CANARD_NODE_ID_UNSET == tr->remote_node_id) && + (tr->port_id <= CANARD_SUBJECT_ID_MAX)) + { + if (local_node_id <= CANARD_NODE_ID_MAX) + { + out = (int32_t) txMakeMessageSessionSpecifier(tr->port_id, local_node_id); + CANARD_ASSERT(out >= 0); + } + else if (payload_size <= presentation_layer_mtu) + { + CANARD_ASSERT((payload != NULL) || (payload_size == 0U)); + const CanardNodeID c = (CanardNodeID) (crcAdd(CRC_INITIAL, payload_size, payload) & CANARD_NODE_ID_MAX); + const uint32_t spec = txMakeMessageSessionSpecifier(tr->port_id, c) | FLAG_ANONYMOUS_MESSAGE; + CANARD_ASSERT(spec <= CAN_EXT_ID_MASK); + out = (int32_t) spec; + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; // Anonymous multi-frame message trs are not allowed. + } + } + else if (((tr->transfer_kind == CanardTransferKindRequest) || (tr->transfer_kind == CanardTransferKindResponse)) && + (tr->remote_node_id <= CANARD_NODE_ID_MAX) && (tr->port_id <= CANARD_SERVICE_ID_MAX)) + { + if (local_node_id <= CANARD_NODE_ID_MAX) + { + out = (int32_t) txMakeServiceSessionSpecifier(tr->port_id, + tr->transfer_kind == CanardTransferKindRequest, + local_node_id, + tr->remote_node_id); + CANARD_ASSERT(out >= 0); + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; // Anonymous service transfers are not allowed. + } + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; + } + + if (out >= 0) + { + const uint32_t prio = (uint32_t) tr->priority; + if (prio <= CANARD_PRIORITY_MAX) + { + const uint32_t id = ((uint32_t) out) | (prio << OFFSET_PRIORITY); + out = (int32_t) id; + } + else + { + out = -CANARD_ERROR_INVALID_ARGUMENT; + } + } + return out; +} + +CANARD_PRIVATE uint8_t txMakeTailByte(const bool start_of_transfer, + const bool end_of_transfer, + const bool toggle, + const CanardTransferID transfer_id) +{ + CANARD_ASSERT(start_of_transfer ? (toggle == INITIAL_TOGGLE_STATE) : true); + return (uint8_t) ((start_of_transfer ? TAIL_START_OF_TRANSFER : 0U) | + (end_of_transfer ? TAIL_END_OF_TRANSFER : 0U) | (toggle ? TAIL_TOGGLE : 0U) | + (transfer_id & CANARD_TRANSFER_ID_MAX)); +} + +/// Takes a frame payload size, returns a new size that is >=x and is rounded up to the nearest valid DLC. +CANARD_PRIVATE size_t txRoundFramePayloadSizeUp(const size_t x) +{ + CANARD_ASSERT(x < (sizeof(CanardCANLengthToDLC) / sizeof(CanardCANLengthToDLC[0]))); + // Suppressing a false-positive out-of-bounds access error from Sonar. Its control flow analyser is misbehaving. + const size_t y = CanardCANLengthToDLC[x]; // NOSONAR + CANARD_ASSERT(y < (sizeof(CanardCANDLCToLength) / sizeof(CanardCANDLCToLength[0]))); + return CanardCANDLCToLength[y]; +} + +/// The item is only allocated and initialized, but NOT included into the queue! The caller needs to do that. +CANARD_PRIVATE TxItem* txAllocateQueueItem(CanardInstance* const ins, + const uint32_t id, + const CanardMicrosecond deadline_usec, + const size_t payload_size) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(payload_size > 0U); + TxItem* const out = (TxItem*) ins->memory_allocate(ins, (sizeof(TxItem) - CANARD_MTU_MAX) + payload_size); + if (out != NULL) + { + out->base.base.up = NULL; + out->base.base.lr[0] = NULL; + out->base.base.lr[1] = NULL; + out->base.base.bf = 0; + + out->base.next_in_transfer = NULL; // Last by default. + out->base.tx_deadline_usec = deadline_usec; + + out->base.frame.payload_size = payload_size; + out->base.frame.payload = out->payload_buffer; + out->base.frame.extended_can_id = id; + } + return out; +} + +/// Frames with identical CAN ID that are added later always compare greater than their counterparts with same CAN ID. +/// This ensures that CAN frames with the same CAN ID are transmitted in the FIFO order. +/// Frames that should be transmitted earlier compare smaller (i.e., put on the left side of the tree). +CANARD_PRIVATE int8_t txAVLPredicate(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. + const CanardTreeNode* const node) +{ + const CanardTxQueueItem* const target = (const CanardTxQueueItem*) user_reference; + const CanardTxQueueItem* const other = (const CanardTxQueueItem*) (const void*) node; + CANARD_ASSERT((target != NULL) && (other != NULL)); + return (target->frame.extended_can_id >= other->frame.extended_can_id) ? +1 : -1; +} + +/// Returns the number of frames enqueued or error (i.e., =1 or <0). +CANARD_PRIVATE int32_t txPushSingleFrame(CanardTxQueue* const que, + CanardInstance* const ins, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const size_t payload_size, + const void* const payload) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT((payload != NULL) || (payload_size == 0)); + const size_t frame_payload_size = txRoundFramePayloadSizeUp(payload_size + 1U); + CANARD_ASSERT(frame_payload_size > payload_size); + const size_t padding_size = frame_payload_size - payload_size - 1U; + CANARD_ASSERT((padding_size + payload_size + 1U) == frame_payload_size); + int32_t out = 0; + TxItem* const tqi = + (que->size < que->capacity) ? txAllocateQueueItem(ins, can_id, deadline_usec, frame_payload_size) : NULL; + if (tqi != NULL) + { + if (payload_size > 0U) // The check is needed to avoid calling memcpy() with a NULL pointer, it's an UB. + { + CANARD_ASSERT(payload != NULL); + // Clang-Tidy raises an error recommending the use of memcpy_s() instead. + // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. + (void) memcpy(&tqi->payload_buffer[0], payload, payload_size); // NOLINT + } + // Clang-Tidy raises an error recommending the use of memset_s() instead. + // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. + (void) memset(&tqi->payload_buffer[payload_size], PADDING_BYTE_VALUE, padding_size); // NOLINT + tqi->payload_buffer[frame_payload_size - 1U] = txMakeTailByte(true, true, true, transfer_id); + // Insert the newly created TX item into the queue. + const CanardTreeNode* const res = cavlSearch(&que->root, &tqi->base.base, &txAVLPredicate, &avlTrivialFactory); + (void) res; + CANARD_ASSERT(res == &tqi->base.base); + que->size++; + CANARD_ASSERT(que->size <= que->capacity); + out = 1; // One frame enqueued. + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + CANARD_ASSERT((out < 0) || (out == 1)); + return out; +} + +/// Produces a chain of Tx queue items for later insertion into the Tx queue. The tail is NULL if OOM. +CANARD_PRIVATE TxChain txGenerateMultiFrameChain(CanardInstance* const ins, + const size_t presentation_layer_mtu, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const size_t payload_size, + const void* const payload) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(presentation_layer_mtu > 0U); + CANARD_ASSERT(payload_size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used. + CANARD_ASSERT(payload != NULL); + + TxChain out = {NULL, NULL, 0}; + const size_t payload_size_with_crc = payload_size + CRC_SIZE_BYTES; + size_t offset = 0U; + TransferCRC crc = crcAdd(CRC_INITIAL, payload_size, payload); + bool toggle = INITIAL_TOGGLE_STATE; + const uint8_t* payload_ptr = (const uint8_t*) payload; + while (offset < payload_size_with_crc) + { + out.size++; + const size_t frame_payload_size_with_tail = + ((payload_size_with_crc - offset) < presentation_layer_mtu) + ? txRoundFramePayloadSizeUp((payload_size_with_crc - offset) + 1U) // Padding in the last frame only. + : (presentation_layer_mtu + 1U); + TxItem* const tqi = txAllocateQueueItem(ins, can_id, deadline_usec, frame_payload_size_with_tail); + if (NULL == out.head) + { + out.head = tqi; + } + else + { + // C std, 6.7.2.1.15: A pointer to a structure object <...> points to its initial member, and vice versa. + // Can't just read tqi->base because tqi may be NULL; https://github.com/OpenCyphal/libcanard/issues/203. + out.tail->base.next_in_transfer = (CanardTxQueueItem*) tqi; + } + out.tail = tqi; + if (NULL == out.tail) + { + break; + } + + // Copy the payload into the frame. + const size_t frame_payload_size = frame_payload_size_with_tail - 1U; + size_t frame_offset = 0U; + if (offset < payload_size) + { + size_t move_size = payload_size - offset; + if (move_size > frame_payload_size) + { + move_size = frame_payload_size; + } + // Clang-Tidy raises an error recommending the use of memcpy_s() instead. + // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. + // SonarQube incorrectly detects a buffer overflow here. + (void) memcpy(&out.tail->payload_buffer[0], payload_ptr, move_size); // NOLINT NOSONAR + frame_offset = frame_offset + move_size; + offset += move_size; + payload_ptr += move_size; + } + + // Handle the last frame of the transfer: it is special because it also contains padding and CRC. + if (offset >= payload_size) + { + // Insert padding -- only in the last frame. Don't forget to include padding into the CRC. + while ((frame_offset + CRC_SIZE_BYTES) < frame_payload_size) + { + out.tail->payload_buffer[frame_offset] = PADDING_BYTE_VALUE; + ++frame_offset; + crc = crcAddByte(crc, PADDING_BYTE_VALUE); + } + + // Insert the CRC. + if ((frame_offset < frame_payload_size) && (offset == payload_size)) + { + // SonarQube incorrectly detects a buffer overflow here. + out.tail->payload_buffer[frame_offset] = (uint8_t) (crc >> BITS_PER_BYTE); // NOSONAR + ++frame_offset; + ++offset; + } + if ((frame_offset < frame_payload_size) && (offset > payload_size)) + { + out.tail->payload_buffer[frame_offset] = (uint8_t) (crc & BYTE_MAX); + ++frame_offset; + ++offset; + } + } + + // Finalize the frame. + CANARD_ASSERT((frame_offset + 1U) == out.tail->base.frame.payload_size); + // SonarQube incorrectly detects a buffer overflow here. + out.tail->payload_buffer[frame_offset] = // NOSONAR + txMakeTailByte(out.head == out.tail, offset >= payload_size_with_crc, toggle, transfer_id); + toggle = !toggle; + } + return out; +} + +/// Returns the number of frames enqueued or error. +CANARD_PRIVATE int32_t txPushMultiFrame(CanardTxQueue* const que, + CanardInstance* const ins, + const size_t presentation_layer_mtu, + const CanardMicrosecond deadline_usec, + const uint32_t can_id, + const CanardTransferID transfer_id, + const size_t payload_size, + const void* const payload) +{ + CANARD_ASSERT((ins != NULL) && (que != NULL)); + CANARD_ASSERT(presentation_layer_mtu > 0U); + CANARD_ASSERT(payload_size > presentation_layer_mtu); // Otherwise, a single-frame transfer should be used. + + int32_t out = 0; // The number of frames enqueued or negated error. + const size_t payload_size_with_crc = payload_size + CRC_SIZE_BYTES; + const size_t num_frames = ((payload_size_with_crc + presentation_layer_mtu) - 1U) / presentation_layer_mtu; + CANARD_ASSERT(num_frames >= 2); + if ((que->size + num_frames) <= que->capacity) // Bail early if we can see that we won't fit anyway. + { + const TxChain sq = txGenerateMultiFrameChain(ins, + presentation_layer_mtu, + deadline_usec, + can_id, + transfer_id, + payload_size, + payload); + if (sq.tail != NULL) + { + CanardTxQueueItem* next = &sq.head->base; + do + { + const CanardTreeNode* const res = + cavlSearch(&que->root, &next->base, &txAVLPredicate, &avlTrivialFactory); + (void) res; + CANARD_ASSERT(res == &next->base); + CANARD_ASSERT(que->root != NULL); + next = next->next_in_transfer; + } while (next != NULL); + CANARD_ASSERT(num_frames == sq.size); + que->size += sq.size; + CANARD_ASSERT(que->size <= que->capacity); + CANARD_ASSERT((sq.size + 0ULL) <= INT32_MAX); // +0 is to suppress warning. + out = (int32_t) sq.size; + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + CanardTxQueueItem* head = &sq.head->base; + while (head != NULL) + { + CanardTxQueueItem* const next = head->next_in_transfer; + ins->memory_free(ins, head); + head = next; + } + } + } + else // We predict that we're going to run out of queue, don't bother serializing the transfer. + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + CANARD_ASSERT((out < 0) || (out >= 2)); + return out; +} + +// --------------------------------------------- RECEPTION --------------------------------------------- + +#define RX_SESSIONS_PER_SUBSCRIPTION (CANARD_NODE_ID_MAX + 1U) + +/// The memory requirement model provided in the documentation assumes that the maximum size of this structure never +/// exceeds 48 bytes on any conventional platform. +/// A user that needs a detailed analysis of the worst-case memory consumption may compute the size of this structure +/// for the particular platform at hand manually or by evaluating its sizeof(). +/// The fields are ordered to minimize the amount of padding on all conventional platforms. +typedef struct CanardInternalRxSession +{ + CanardMicrosecond transfer_timestamp_usec; ///< Timestamp of the last received start-of-transfer. + size_t total_payload_size; ///< The payload size before the implicit truncation, including the CRC. + size_t payload_size; ///< How many bytes received so far. + uint8_t* payload; ///< Dynamically allocated and handed off to the application when done. + TransferCRC calculated_crc; ///< Updated with the received payload in real time. + CanardTransferID transfer_id; + uint8_t redundant_iface_index; ///< Arbitrary value in [0, 255]. + bool toggle; +} CanardInternalRxSession; + +/// High-level transport frame model. +typedef struct +{ + CanardMicrosecond timestamp_usec; + CanardPriority priority; + CanardTransferKind transfer_kind; + CanardPortID port_id; + CanardNodeID source_node_id; + CanardNodeID destination_node_id; + CanardTransferID transfer_id; + bool start_of_transfer; + bool end_of_transfer; + bool toggle; + size_t payload_size; + const void* payload; +} RxFrameModel; + +/// Returns truth if the frame is valid and parsed successfully. False if the frame is not a valid Cyphal/CAN frame. +CANARD_PRIVATE bool rxTryParseFrame(const CanardMicrosecond timestamp_usec, + const CanardFrame* const frame, + RxFrameModel* const out) +{ + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->extended_can_id <= CAN_EXT_ID_MASK); + CANARD_ASSERT(out != NULL); + bool valid = false; + if (frame->payload_size > 0) + { + CANARD_ASSERT(frame->payload != NULL); + out->timestamp_usec = timestamp_usec; + + // CAN ID parsing. + const uint32_t can_id = frame->extended_can_id; + out->priority = (CanardPriority) ((can_id >> OFFSET_PRIORITY) & CANARD_PRIORITY_MAX); + out->source_node_id = (CanardNodeID) (can_id & CANARD_NODE_ID_MAX); + if (0 == (can_id & FLAG_SERVICE_NOT_MESSAGE)) + { + out->transfer_kind = CanardTransferKindMessage; + out->port_id = (CanardPortID) ((can_id >> OFFSET_SUBJECT_ID) & CANARD_SUBJECT_ID_MAX); + if ((can_id & FLAG_ANONYMOUS_MESSAGE) != 0) + { + out->source_node_id = CANARD_NODE_ID_UNSET; + } + out->destination_node_id = CANARD_NODE_ID_UNSET; + // Reserved bits may be unreserved in the future. + valid = (0 == (can_id & FLAG_RESERVED_23)) && (0 == (can_id & FLAG_RESERVED_07)); + } + else + { + out->transfer_kind = + ((can_id & FLAG_REQUEST_NOT_RESPONSE) != 0) ? CanardTransferKindRequest : CanardTransferKindResponse; + out->port_id = (CanardPortID) ((can_id >> OFFSET_SERVICE_ID) & CANARD_SERVICE_ID_MAX); + out->destination_node_id = (CanardNodeID) ((can_id >> OFFSET_DST_NODE_ID) & CANARD_NODE_ID_MAX); + // The reserved bit may be unreserved in the future. It may be used to extend the service-ID to 10 bits. + // Per Specification, source cannot be the same as the destination. + valid = (0 == (can_id & FLAG_RESERVED_23)) && (out->source_node_id != out->destination_node_id); + } + + // Payload parsing. + out->payload_size = frame->payload_size - 1U; // Cut off the tail byte. + out->payload = frame->payload; + + // Tail byte parsing. + // Intentional violation of MISRA: pointer arithmetics is required to locate the tail byte. Unavoidable. + const uint8_t tail = *(((const uint8_t*) out->payload) + out->payload_size); // NOSONAR + out->transfer_id = tail & CANARD_TRANSFER_ID_MAX; + out->start_of_transfer = ((tail & TAIL_START_OF_TRANSFER) != 0); + out->end_of_transfer = ((tail & TAIL_END_OF_TRANSFER) != 0); + out->toggle = ((tail & TAIL_TOGGLE) != 0); + + // Final validation. + // Protocol version check: if SOT is set, then the toggle shall also be set. + valid = valid && ((!out->start_of_transfer) || (INITIAL_TOGGLE_STATE == out->toggle)); + // Anonymous transfers can be only single-frame transfers. + valid = valid && + ((out->start_of_transfer && out->end_of_transfer) || (CANARD_NODE_ID_UNSET != out->source_node_id)); + // Non-last frames of a multi-frame transfer shall utilize the MTU fully. + valid = valid && ((out->payload_size >= MFT_NON_LAST_FRAME_PAYLOAD_MIN) || out->end_of_transfer); + // A frame that is a part of a multi-frame transfer cannot be empty (tail byte not included). + valid = valid && ((out->payload_size > 0) || (out->start_of_transfer && out->end_of_transfer)); + } + return valid; +} + +CANARD_PRIVATE void rxInitTransferMetadataFromFrame(const RxFrameModel* const frame, + CanardTransferMetadata* const out_transfer) +{ + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(out_transfer != NULL); + out_transfer->priority = frame->priority; + out_transfer->transfer_kind = frame->transfer_kind; + out_transfer->port_id = frame->port_id; + out_transfer->remote_node_id = frame->source_node_id; + out_transfer->transfer_id = frame->transfer_id; +} + +/// The implementation is borrowed from the Specification. +CANARD_PRIVATE uint8_t rxComputeTransferIDDifference(const uint8_t a, const uint8_t b) +{ + CANARD_ASSERT(a <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(b <= CANARD_TRANSFER_ID_MAX); + int16_t diff = (int16_t) (((int16_t) a) - ((int16_t) b)); + if (diff < 0) + { + const uint8_t modulo = 1U << CANARD_TRANSFER_ID_BIT_LENGTH; + diff = (int16_t) (diff + (int16_t) modulo); + } + return (uint8_t) diff; +} + +CANARD_PRIVATE int8_t rxSessionWritePayload(CanardInstance* const ins, + CanardInternalRxSession* const rxs, + const size_t extent, + const size_t payload_size, + const void* const payload) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT((payload != NULL) || (payload_size == 0U)); + CANARD_ASSERT(rxs->payload_size <= extent); // This invariant is enforced by the subscription logic. + CANARD_ASSERT(rxs->payload_size <= rxs->total_payload_size); + + rxs->total_payload_size += payload_size; + + // Allocate the payload lazily, as late as possible. + if ((NULL == rxs->payload) && (extent > 0U)) + { + CANARD_ASSERT(rxs->payload_size == 0); + rxs->payload = ins->memory_allocate(ins, extent); + } + + int8_t out = 0; + if (rxs->payload != NULL) + { + // Copy the payload into the contiguous buffer. Apply the implicit truncation rule if necessary. + size_t bytes_to_copy = payload_size; + if ((rxs->payload_size + bytes_to_copy) > extent) + { + CANARD_ASSERT(rxs->payload_size <= extent); + bytes_to_copy = extent - rxs->payload_size; + CANARD_ASSERT((rxs->payload_size + bytes_to_copy) == extent); + CANARD_ASSERT(bytes_to_copy < payload_size); + } + // This memcpy() call here is one of the two variable-complexity operations in the RX pipeline; + // the other one is the search of the matching subscription state. + // Excepting these two cases, the entire RX pipeline contains neither loops nor recursion. + // Intentional violation of MISRA: indexing on a pointer. This is done to avoid pointer arithmetics. + // Clang-Tidy raises an error recommending the use of memcpy_s() instead. + // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. + (void) memcpy(&rxs->payload[rxs->payload_size], payload, bytes_to_copy); // NOLINT NOSONAR + rxs->payload_size += bytes_to_copy; + CANARD_ASSERT(rxs->payload_size <= extent); + } + else + { + CANARD_ASSERT(rxs->payload_size == 0); + out = (extent > 0U) ? -CANARD_ERROR_OUT_OF_MEMORY : 0; + } + CANARD_ASSERT(out <= 0); + return out; +} + +CANARD_PRIVATE void rxSessionRestart(CanardInstance* const ins, CanardInternalRxSession* const rxs) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + ins->memory_free(ins, rxs->payload); // May be NULL, which is OK. + rxs->total_payload_size = 0U; + rxs->payload_size = 0U; + rxs->payload = NULL; + rxs->calculated_crc = CRC_INITIAL; + rxs->transfer_id = (CanardTransferID) ((rxs->transfer_id + 1U) & CANARD_TRANSFER_ID_MAX); + // The transport index is retained. + rxs->toggle = INITIAL_TOGGLE_STATE; +} + +CANARD_PRIVATE int8_t rxSessionAcceptFrame(CanardInstance* const ins, + CanardInternalRxSession* const rxs, + const RxFrameModel* const frame, + const size_t extent, + CanardRxTransfer* const out_transfer) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(out_transfer != NULL); + + if (frame->start_of_transfer) // The transfer timestamp is the timestamp of its first frame. + { + rxs->transfer_timestamp_usec = frame->timestamp_usec; + } + + const bool single_frame = frame->start_of_transfer && frame->end_of_transfer; + if (!single_frame) + { + // Update the CRC. Observe that the implicit truncation rule may apply here: the payload may be + // truncated, but its CRC is validated always anyway. + rxs->calculated_crc = crcAdd(rxs->calculated_crc, frame->payload_size, frame->payload); + } + + int8_t out = rxSessionWritePayload(ins, rxs, extent, frame->payload_size, frame->payload); + if (out < 0) + { + CANARD_ASSERT(-CANARD_ERROR_OUT_OF_MEMORY == out); + rxSessionRestart(ins, rxs); // Out-of-memory. + } + else if (frame->end_of_transfer) + { + CANARD_ASSERT(0 == out); + if (single_frame || (CRC_RESIDUE == rxs->calculated_crc)) + { + out = 1; // One transfer received, notify the application. + rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata); + out_transfer->timestamp_usec = rxs->transfer_timestamp_usec; + out_transfer->payload_size = rxs->payload_size; + out_transfer->payload = rxs->payload; + + // Cut off the CRC from the payload if it's there -- we don't want to expose it to the user. + CANARD_ASSERT(rxs->total_payload_size >= rxs->payload_size); + const size_t truncated_amount = rxs->total_payload_size - rxs->payload_size; + if ((!single_frame) && (CRC_SIZE_BYTES > truncated_amount)) // Single-frame transfers don't have CRC. + { + CANARD_ASSERT(out_transfer->payload_size >= (CRC_SIZE_BYTES - truncated_amount)); + out_transfer->payload_size -= CRC_SIZE_BYTES - truncated_amount; + } + + rxs->payload = NULL; // Ownership passed over to the application, nullify to prevent freeing. + } + rxSessionRestart(ins, rxs); // Successful completion. + } + else + { + rxs->toggle = !rxs->toggle; + } + return out; +} + +/// Evaluates the state of the RX session with respect to time and the new frame, and restarts it if necessary. +/// The next step is to accept the frame if the transfer-ID, toggle but, and transport index match; reject otherwise. +/// The logic of this function is simple: it restarts the reassembler if the start-of-transfer flag is set and +/// any two of the three conditions are met: +/// +/// - The frame has arrived over the same interface as the previous transfer. +/// - New transfer-ID is detected. +/// - The transfer-ID timeout has expired. +/// +/// Notice that mere TID-timeout is not enough to restart to prevent the interface index oscillation; +/// while this is not visible at the application layer, it may delay the transfer arrival. +CANARD_PRIVATE void rxSessionSynchronize(CanardInternalRxSession* const rxs, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + const CanardMicrosecond transfer_id_timeout_usec) +{ + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(rxs->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + + const bool same_transport = rxs->redundant_iface_index == redundant_iface_index; + // Examples: rxComputeTransferIDDifference(2, 3)==31 + // rxComputeTransferIDDifference(2, 2)==0 + // rxComputeTransferIDDifference(2, 1)==1 + const bool tid_new = rxComputeTransferIDDifference(rxs->transfer_id, frame->transfer_id) > 1; + // The transfer ID timeout is measured relative to the timestamp of the last start-of-transfer frame. + const bool tid_timeout = (frame->timestamp_usec > rxs->transfer_timestamp_usec) && + ((frame->timestamp_usec - rxs->transfer_timestamp_usec) > transfer_id_timeout_usec); + + const bool restartable = (same_transport && tid_new) || // + (same_transport && tid_timeout) || // + (tid_new && tid_timeout); + // Restarting the transfer reassembly only makes sense if the new frame is a start of transfer. + // Otherwise, the new transfer would be impossible to reassemble anyway since the first frame is lost. + if (frame->start_of_transfer && restartable) + { + CANARD_ASSERT(frame->start_of_transfer); + rxs->total_payload_size = 0U; + rxs->payload_size = 0U; // The buffer is not released because we still need it. + rxs->calculated_crc = CRC_INITIAL; + rxs->transfer_id = frame->transfer_id; + rxs->toggle = INITIAL_TOGGLE_STATE; + rxs->redundant_iface_index = redundant_iface_index; + } +} + +/// RX session state machine update is the most intricate part of any Cyphal transport implementation. +/// The state model used here is derived from the reference pseudocode given in the original UAVCAN v0 specification. +/// The Cyphal/CAN v1 specification, which this library is an implementation of, does not provide any reference +/// pseudocode. Instead, it takes a higher-level, more abstract approach, where only the high-level requirements +/// are given and the particular algorithms are left to be implementation-defined. Such abstract approach is much +/// advantageous because it allows implementers to choose whatever solution works best for the specific application at +/// hand, while the wire compatibility is still guaranteed by the high-level requirements given in the specification. +CANARD_PRIVATE int8_t rxSessionUpdate(CanardInstance* const ins, + CanardInternalRxSession* const rxs, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + const CanardMicrosecond transfer_id_timeout_usec, + const size_t extent, + CanardRxTransfer* const out_transfer) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(rxs != NULL); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(out_transfer != NULL); + CANARD_ASSERT(rxs->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + rxSessionSynchronize(rxs, frame, redundant_iface_index, transfer_id_timeout_usec); + int8_t out = 0; + // The purpose of the correct_start check is to reduce the possibility of accepting a malformed multi-frame + // transfer in the event of a CRC collision. The scenario where this failure mode would manifest is as follows: + // 1. A valid transfer (whether single- or multi-frame) is accepted with TID=X. + // 2. All frames of the subsequent multi-frame transfer with TID=X+1 are lost except for the last one. + // 3. The CRC of said multi-frame transfer happens to yield the correct residue when applied to the fragment + // of the payload contained in the last frame of the transfer (a CRC collision is in effect). + // 4. The last frame of the multi-frame transfer is erroneously accepted even though it is malformed. + // The correct_start check eliminates this failure mode by ensuring that the first frame is observed. + // See https://github.com/OpenCyphal/libcanard/issues/189. + const bool correct_iface = (rxs->redundant_iface_index == redundant_iface_index); + const bool correct_toggle = (frame->toggle == rxs->toggle); + const bool correct_tid = (frame->transfer_id == rxs->transfer_id); + const bool correct_start = frame->start_of_transfer // + ? (0 == rxs->total_payload_size) + : (rxs->total_payload_size > 0); + if (correct_iface && correct_toggle && correct_tid && correct_start) + { + out = rxSessionAcceptFrame(ins, rxs, frame, extent, out_transfer); + } + return out; +} + +CANARD_PRIVATE int8_t rxAcceptFrame(CanardInstance* const ins, + CanardRxSubscription* const subscription, + const RxFrameModel* const frame, + const uint8_t redundant_iface_index, + CanardRxTransfer* const out_transfer) +{ + CANARD_ASSERT(ins != NULL); + CANARD_ASSERT(subscription != NULL); + CANARD_ASSERT(subscription->port_id == frame->port_id); + CANARD_ASSERT(frame != NULL); + CANARD_ASSERT(frame->payload != NULL); + CANARD_ASSERT(frame->transfer_id <= CANARD_TRANSFER_ID_MAX); + CANARD_ASSERT((CANARD_NODE_ID_UNSET == frame->destination_node_id) || (ins->node_id == frame->destination_node_id)); + CANARD_ASSERT(out_transfer != NULL); + + int8_t out = 0; + if (frame->source_node_id <= CANARD_NODE_ID_MAX) + { + // If such session does not exist, create it. This only makes sense if this is the first frame of a + // transfer, otherwise, we won't be able to receive the transfer anyway so we don't bother. + if ((NULL == subscription->sessions[frame->source_node_id]) && frame->start_of_transfer) + { + CanardInternalRxSession* const rxs = + (CanardInternalRxSession*) ins->memory_allocate(ins, sizeof(CanardInternalRxSession)); + subscription->sessions[frame->source_node_id] = rxs; + if (rxs != NULL) + { + rxs->transfer_timestamp_usec = frame->timestamp_usec; + rxs->total_payload_size = 0U; + rxs->payload_size = 0U; + rxs->payload = NULL; + rxs->calculated_crc = CRC_INITIAL; + rxs->transfer_id = frame->transfer_id; + rxs->redundant_iface_index = redundant_iface_index; + rxs->toggle = INITIAL_TOGGLE_STATE; + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + } + // There are two possible reasons why the session may not exist: 1. OOM; 2. SOT-miss. + if (subscription->sessions[frame->source_node_id] != NULL) + { + CANARD_ASSERT(out == 0); + out = rxSessionUpdate(ins, + subscription->sessions[frame->source_node_id], + frame, + redundant_iface_index, + subscription->transfer_id_timeout_usec, + subscription->extent, + out_transfer); + } + } + else + { + CANARD_ASSERT(frame->source_node_id == CANARD_NODE_ID_UNSET); + // Anonymous transfers are stateless. No need to update the state machine, just blindly accept it. + // We have to copy the data into an allocated storage because the API expects it: the lifetime shall be + // independent of the input data and the memory shall be free-able. + const size_t payload_size = + (subscription->extent < frame->payload_size) ? subscription->extent : frame->payload_size; + void* const payload = ins->memory_allocate(ins, payload_size); + if (payload != NULL) + { + rxInitTransferMetadataFromFrame(frame, &out_transfer->metadata); + out_transfer->timestamp_usec = frame->timestamp_usec; + out_transfer->payload_size = payload_size; + out_transfer->payload = payload; + // Clang-Tidy raises an error recommending the use of memcpy_s() instead. + // We ignore it because the safe functions are poorly supported; reliance on them may limit the portability. + (void) memcpy(payload, frame->payload, payload_size); // NOLINT + out = 1; + } + else + { + out = -CANARD_ERROR_OUT_OF_MEMORY; + } + } + return out; +} + +CANARD_PRIVATE int8_t +rxSubscriptionPredicateOnPortID(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. + const CanardTreeNode* const node) +{ + const CanardPortID sought = *((const CanardPortID*) user_reference); + const CanardPortID other = ((const CanardRxSubscription*) (const void*) node)->port_id; + static const int8_t NegPos[2] = {-1, +1}; + // Clang-Tidy mistakenly identifies a narrowing cast to int8_t here, which is incorrect. + return (sought == other) ? 0 : NegPos[sought > other]; // NOLINT no narrowing conversion is taking place here +} + +CANARD_PRIVATE int8_t +rxSubscriptionPredicateOnStruct(void* const user_reference, // NOSONAR Cavl API requires pointer to non-const. + const CanardTreeNode* const node) +{ + return rxSubscriptionPredicateOnPortID(&((CanardRxSubscription*) user_reference)->port_id, node); +} + +// --------------------------------------------- PUBLIC API --------------------------------------------- + +const uint8_t CanardCANDLCToLength[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64}; +const uint8_t CanardCANLengthToDLC[65] = { + 0, 1, 2, 3, 4, 5, 6, 7, 8, // 0-8 + 9, 9, 9, 9, // 9-12 + 10, 10, 10, 10, // 13-16 + 11, 11, 11, 11, // 17-20 + 12, 12, 12, 12, // 21-24 + 13, 13, 13, 13, 13, 13, 13, 13, // 25-32 + 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, // 33-48 + 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, // 49-64 +}; + +CanardInstance canardInit(const CanardMemoryAllocate memory_allocate, const CanardMemoryFree memory_free) +{ + CANARD_ASSERT(memory_allocate != NULL); + CANARD_ASSERT(memory_free != NULL); + const CanardInstance out = { + .user_reference = NULL, + .node_id = CANARD_NODE_ID_UNSET, + .memory_allocate = memory_allocate, + .memory_free = memory_free, + .rx_subscriptions = {NULL, NULL, NULL}, + }; + return out; +} + +CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes) +{ + CanardTxQueue out = { + .capacity = capacity, + .mtu_bytes = mtu_bytes, + .size = 0, + .root = NULL, + .user_reference = NULL, + }; + return out; +} + +int32_t canardTxPush(CanardTxQueue* const que, + CanardInstance* const ins, + const CanardMicrosecond tx_deadline_usec, + const CanardTransferMetadata* const metadata, + const size_t payload_size, + const void* const payload) +{ + int32_t out = -CANARD_ERROR_INVALID_ARGUMENT; + if ((ins != NULL) && (que != NULL) && (metadata != NULL) && ((payload != NULL) || (0U == payload_size))) + { + const size_t pl_mtu = adjustPresentationLayerMTU(que->mtu_bytes); + const int32_t maybe_can_id = txMakeCANID(metadata, payload_size, payload, ins->node_id, pl_mtu); + if (maybe_can_id >= 0) + { + if (payload_size <= pl_mtu) + { + out = txPushSingleFrame(que, + ins, + tx_deadline_usec, + (uint32_t) maybe_can_id, + metadata->transfer_id, + payload_size, + payload); + CANARD_ASSERT((out < 0) || (out == 1)); + } + else + { + out = txPushMultiFrame(que, + ins, + pl_mtu, + tx_deadline_usec, + (uint32_t) maybe_can_id, + metadata->transfer_id, + payload_size, + payload); + CANARD_ASSERT((out < 0) || (out >= 2)); + } + } + else + { + out = maybe_can_id; + } + } + CANARD_ASSERT(out != 0); + return out; +} + +const CanardTxQueueItem* canardTxPeek(const CanardTxQueue* const que) +{ + const CanardTxQueueItem* out = NULL; + if (que != NULL) + { + // Paragraph 6.7.2.1.15 of the C standard says: + // A pointer to a structure object, suitably converted, points to its initial member, and vice versa. + out = (const CanardTxQueueItem*) (void*) cavlFindExtremum(que->root, false); + } + return out; +} + +CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem* const item) +{ + CanardTxQueueItem* out = NULL; + if ((que != NULL) && (item != NULL)) + { + // Intentional violation of MISRA: casting away const qualifier. This is considered safe because the API + // contract dictates that the pointer shall point to a mutable entity in RAM previously allocated by the + // memory manager. It is difficult to avoid this cast in this context. + out = (CanardTxQueueItem*) item; // NOSONAR casting away const qualifier. + // Paragraph 6.7.2.1.15 of the C standard says: + // A pointer to a structure object, suitably converted, points to its initial member, and vice versa. + // Note that the highest-priority frame is always a leaf node in the AVL tree, which means that it is very + // cheap to remove. + cavlRemove(&que->root, &item->base); + que->size--; + } + return out; +} + +int8_t canardRxAccept(CanardInstance* const ins, + const CanardMicrosecond timestamp_usec, + const CanardFrame* const frame, + const uint8_t redundant_iface_index, + CanardRxTransfer* const out_transfer, + CanardRxSubscription** const out_subscription) +{ + int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; + if ((ins != NULL) && (out_transfer != NULL) && (frame != NULL) && (frame->extended_can_id <= CAN_EXT_ID_MASK) && + ((frame->payload != NULL) || (0 == frame->payload_size))) + { + RxFrameModel model = {0}; + if (rxTryParseFrame(timestamp_usec, frame, &model)) + { + if ((CANARD_NODE_ID_UNSET == model.destination_node_id) || (ins->node_id == model.destination_node_id)) + { + // This is the reason the function has a logarithmic time complexity of the number of subscriptions. + // Note also that this one of the two variable-complexity operations in the RX pipeline; the other one + // is memcpy(). Excepting these two cases, the entire RX pipeline contains neither loops nor recursion. + CanardRxSubscription* const sub = + (CanardRxSubscription*) (void*) cavlSearch(&ins->rx_subscriptions[(size_t) model.transfer_kind], + &model.port_id, + &rxSubscriptionPredicateOnPortID, + NULL); + if (out_subscription != NULL) + { + *out_subscription = sub; // Expose selected instance to the caller. + } + if (sub != NULL) + { + CANARD_ASSERT(sub->port_id == model.port_id); + out = rxAcceptFrame(ins, sub, &model, redundant_iface_index, out_transfer); + } + else + { + out = 0; // No matching subscription. + } + } + else + { + out = 0; // Mis-addressed frame (normally it should be filtered out by the hardware). + } + } + else + { + out = 0; // A non-Cyphal/CAN input frame. + } + } + CANARD_ASSERT(out <= 1); + return out; +} + +int8_t canardRxSubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id, + const size_t extent, + const CanardMicrosecond transfer_id_timeout_usec, + CanardRxSubscription* const out_subscription) +{ + int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; + const size_t tk = (size_t) transfer_kind; + if ((ins != NULL) && (out_subscription != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) + { + // Reset to the initial state. This is absolutely critical because the new payload size limit may be larger + // than the old value; if there are any payload buffers allocated, we may overrun them because they are shorter + // than the new payload limit. So we clear the subscription and thus ensure that no overrun may occur. + out = canardRxUnsubscribe(ins, transfer_kind, port_id); + if (out >= 0) + { + out_subscription->transfer_id_timeout_usec = transfer_id_timeout_usec; + out_subscription->extent = extent; + out_subscription->port_id = port_id; + for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++) + { + // The sessions will be created ad-hoc. Normally, for a low-jitter deterministic system, + // we could have pre-allocated sessions here, but that requires too much memory to be feasible. + // We could accept an extra argument that would instruct us to pre-allocate sessions here? + out_subscription->sessions[i] = NULL; + } + const CanardTreeNode* const res = cavlSearch(&ins->rx_subscriptions[tk], + out_subscription, + &rxSubscriptionPredicateOnStruct, + &avlTrivialFactory); + (void) res; + CANARD_ASSERT(res == &out_subscription->base); + out = (out > 0) ? 0 : 1; + } + } + return out; +} + +int8_t canardRxUnsubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id) +{ + int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; + const size_t tk = (size_t) transfer_kind; + if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) + { + CanardPortID port_id_mutable = port_id; + CanardRxSubscription* const sub = (CanardRxSubscription*) (void*) + cavlSearch(&ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID, NULL); + if (sub != NULL) + { + cavlRemove(&ins->rx_subscriptions[tk], &sub->base); + CANARD_ASSERT(sub->port_id == port_id); + out = 1; + for (size_t i = 0; i < RX_SESSIONS_PER_SUBSCRIPTION; i++) + { + ins->memory_free(ins, (sub->sessions[i] != NULL) ? sub->sessions[i]->payload : NULL); + ins->memory_free(ins, sub->sessions[i]); + sub->sessions[i] = NULL; + } + } + else + { + out = 0; + } + } + return out; +} + +int8_t canardRxGetSubscription(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id, + CanardRxSubscription** const out_subscription) +{ + int8_t out = -CANARD_ERROR_INVALID_ARGUMENT; + const size_t tk = (size_t) transfer_kind; + if ((ins != NULL) && (tk < CANARD_NUM_TRANSFER_KINDS)) + { + CanardPortID port_id_mutable = port_id; + CanardRxSubscription* const sub = (CanardRxSubscription*) (void*) + cavlSearch(&ins->rx_subscriptions[tk], &port_id_mutable, &rxSubscriptionPredicateOnPortID, NULL); + if (sub != NULL) + { + CANARD_ASSERT(sub->port_id == port_id); + if (out_subscription != NULL) + { + *out_subscription = sub; + } + out = 1; + } + else + { + out = 0; + } + } + return out; +} + +CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id) +{ + CanardFilter out = {0}; + + out.extended_can_id = ((uint32_t) subject_id) << OFFSET_SUBJECT_ID; + out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_07 | (CANARD_SUBJECT_ID_MAX << OFFSET_SUBJECT_ID); + + return out; +} + +CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id) +{ + CanardFilter out = {0}; + + out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) service_id) << OFFSET_SERVICE_ID) | + (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID); + out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_SERVICE_ID_MAX << OFFSET_SERVICE_ID) | + (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID); + + return out; +} + +CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id) +{ + CanardFilter out = {0}; + + out.extended_can_id = FLAG_SERVICE_NOT_MESSAGE | (((uint32_t) local_node_id) << OFFSET_DST_NODE_ID); + out.extended_mask = FLAG_SERVICE_NOT_MESSAGE | FLAG_RESERVED_23 | (CANARD_NODE_ID_MAX << OFFSET_DST_NODE_ID); + + return out; +} + +CanardFilter canardConsolidateFilters(const CanardFilter* a, const CanardFilter* b) +{ + CanardFilter out = {0}; + + out.extended_mask = a->extended_mask & b->extended_mask & ~(a->extended_can_id ^ b->extended_can_id); + out.extended_can_id = a->extended_can_id & out.extended_mask; + + return out; +} diff --git a/components/esp_canard/include/_canard_cavl.h b/components/esp_canard/include/_canard_cavl.h new file mode 100644 index 0000000..15a813b --- /dev/null +++ b/components/esp_canard/include/_canard_cavl.h @@ -0,0 +1,337 @@ +/// Source: https://github.com/pavel-kirienko/cavl +/// +/// Cavl is a single-header C library providing an implementation of AVL tree suitable for deeply embedded systems. +/// To integrate it into your project, simply copy this file into your source tree. Read the API docs below. +/// +/// See also O1Heap -- a deterministic memory manager for hard-real-time +/// high-integrity embedded systems. +/// +/// Copyright (c) 2021 Pavel Kirienko +/// +/// Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated +/// documentation files (the "Software"), to deal in the Software without restriction, including without limitation +/// the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, +/// and to permit persons to whom the Software is furnished to do so, subject to the following conditions: +/// +/// The above copyright notice and this permission notice shall be included in all copies or substantial portions of +/// the Software. +/// +/// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +/// WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS +/// OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR +/// OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +#pragma once + +#include "canard.h" + +/// Modified for use with Libcanard: use the same assertion check macro if provided. +#ifdef CANARD_ASSERT +# define CAVL_ASSERT CANARD_ASSERT +#else +// Intentional violation of MISRA: inclusion not at the top of the file to eliminate unnecessary dependency on assert.h. +# include // NOSONAR +# define CAVL_ASSERT assert +#endif + +#ifdef __cplusplus +// This is, strictly speaking, useless because we do not define any functions with external linkage here, +// but it tells static analyzers that what follows should be interpreted as C code rather than C++. +extern "C" { +#endif + +// ---------------------------------------- PUBLIC API SECTION ---------------------------------------- + +/// Modified for use with Libcanard: expose the Cavl structure via public API as CanardTreeNode. +typedef CanardTreeNode Cavl; + +/// Returns POSITIVE if the search target is GREATER than the provided node, negative if smaller, zero on match (found). +/// Values other than {-1, 0, +1} are not recommended to avoid overflow during the narrowing conversion of the result. +typedef int8_t (*CavlPredicate)(void* user_reference, const Cavl* node); + +/// If provided, the factory will be invoked when the sought node does not exist in the tree. +/// It is expected to return a new node that will be inserted immediately (without the need to traverse the tree again). +/// If the factory returns NULL or is not provided, the tree is not modified. +typedef Cavl* (*CavlFactory)(void* user_reference); + +/// Look for a node in the tree using the specified search predicate. The worst-case complexity is O(log n). +/// - If the node is found, return it. +/// - If the node is not found and the factory is NULL, return NULL. +/// - Otherwise, construct a new node using the factory; if the result is not NULL, insert it; return the result. +/// The user_reference is passed into the predicate & factory unmodified. +/// The root node may be replaced in the process. +/// If predicate is NULL, returns NULL. +static inline Cavl* cavlSearch(Cavl** const root, + void* const user_reference, + const CavlPredicate predicate, + const CavlFactory factory); + +/// Remove the specified node from its tree. The root node may be replaced in the process. +/// The worst-case complexity is O(log n). +/// The function has no effect if either of the pointers are NULL. +/// If the node is not in the tree, the behavior is undefined; it may create cycles in the tree which is deadly. +/// It is safe to pass the result of cavlSearch() directly as the second argument: +/// cavlRemove(&root, cavlSearch(&root, user_reference, search_predicate, NULL)); +/// It is recommended to invalidate the pointers stored in the node after its removal. +static inline void cavlRemove(Cavl** const root, const Cavl* const node); + +/// Return the min-/max-valued node stored in the tree, depending on the flag. This is an extremely fast query. +/// Returns NULL iff the argument is NULL (i.e., the tree is empty). The worst-case complexity is O(log n). +static inline Cavl* cavlFindExtremum(Cavl* const root, const bool maximum) +{ + Cavl* result = NULL; + Cavl* c = root; + while (c != NULL) + { + result = c; + c = c->lr[maximum]; + } + return result; +} + +// ---------------------------------------- END OF PUBLIC API SECTION ---------------------------------------- +// ---------------------------------------- POLICE LINE DO NOT CROSS ---------------------------------------- + +/// INTERNAL USE ONLY. Makes the '!r' child of node 'x' its parent; i.e., rotates 'x' toward 'r'. +static inline void cavlPrivateRotate(Cavl* const x, const bool r) +{ + CAVL_ASSERT((x != NULL) && (x->lr[!r] != NULL) && ((x->bf >= -1) && (x->bf <= +1))); + Cavl* const z = x->lr[!r]; + if (x->up != NULL) + { + x->up->lr[x->up->lr[1] == x] = z; + } + z->up = x->up; + x->up = z; + x->lr[!r] = z->lr[r]; + if (x->lr[!r] != NULL) + { + x->lr[!r]->up = x; + } + z->lr[r] = x; +} + +/// INTERNAL USE ONLY. +/// Accepts a node and how its balance factor needs to be changed -- either +1 or -1. +/// Returns the new node to replace the old one if tree rotation took place, same node otherwise. +static inline Cavl* cavlPrivateAdjustBalance(Cavl* const x, const bool increment) +{ + CAVL_ASSERT((x != NULL) && ((x->bf >= -1) && (x->bf <= +1))); + Cavl* out = x; + const int8_t new_bf = (int8_t) (x->bf + (increment ? +1 : -1)); + if ((new_bf < -1) || (new_bf > 1)) + { + const bool r = new_bf < 0; // bf<0 if left-heavy --> right rotation is needed. + const int8_t sign = r ? +1 : -1; // Positive if we are rotating right. + Cavl* const z = x->lr[!r]; + CAVL_ASSERT(z != NULL); // Heavy side cannot be empty. + if ((z->bf * sign) <= 0) // Parent and child are heavy on the same side or the child is balanced. + { + out = z; + cavlPrivateRotate(x, r); + if (0 == z->bf) + { + x->bf = (int8_t) (-sign); + z->bf = (int8_t) (+sign); + } + else + { + x->bf = 0; + z->bf = 0; + } + } + else // Otherwise, the child needs to be rotated in the opposite direction first. + { + Cavl* const y = z->lr[r]; + CAVL_ASSERT(y != NULL); // Heavy side cannot be empty. + out = y; + cavlPrivateRotate(z, !r); + cavlPrivateRotate(x, r); + if ((y->bf * sign) < 0) + { + x->bf = (int8_t) (+sign); + y->bf = 0; + z->bf = 0; + } + else if ((y->bf * sign) > 0) + { + x->bf = 0; + y->bf = 0; + z->bf = (int8_t) (-sign); + } + else + { + x->bf = 0; + z->bf = 0; + } + } + } + else + { + x->bf = new_bf; // Balancing not needed, just update the balance factor and call it a day. + } + return out; +} + +/// INTERNAL USE ONLY. +/// Takes the culprit node (the one that is added); returns NULL or the root of the tree (possibly new one). +/// When adding a new node, set its balance factor to zero and call this function to propagate the changes upward. +static inline Cavl* cavlPrivateRetraceOnGrowth(Cavl* const added) +{ + CAVL_ASSERT((added != NULL) && (0 == added->bf)); + Cavl* c = added; // Child + Cavl* p = added->up; // Parent + while (p != NULL) + { + const bool r = p->lr[1] == c; // c is the right child of parent + CAVL_ASSERT(p->lr[r] == c); + c = cavlPrivateAdjustBalance(p, r); + p = c->up; + if (0 == c->bf) + { // The height change of the subtree made this parent perfectly balanced (as all things should be), + break; // hence, the height of the outer subtree is unchanged, so upper balance factors are unchanged. + } + } + CAVL_ASSERT(c != NULL); + return (NULL == p) ? c : NULL; // New root or nothing. +} + +static inline Cavl* cavlSearch(Cavl** const root, + void* const user_reference, + const CavlPredicate predicate, + const CavlFactory factory) +{ + Cavl* out = NULL; + if ((root != NULL) && (predicate != NULL)) + { + Cavl* up = *root; + Cavl** n = root; + while (*n != NULL) + { + const int8_t cmp = predicate(user_reference, *n); + if (0 == cmp) + { + out = *n; + break; + } + up = *n; + n = &(*n)->lr[cmp > 0]; + CAVL_ASSERT((NULL == *n) || ((*n)->up == up)); + } + if (NULL == out) + { + out = (NULL == factory) ? NULL : factory(user_reference); + if (out != NULL) + { + *n = out; // Overwrite the pointer to the new node in the parent node. + out->lr[0] = NULL; + out->lr[1] = NULL; + out->up = up; + out->bf = 0; + Cavl* const rt = cavlPrivateRetraceOnGrowth(out); + if (rt != NULL) + { + *root = rt; + } + } + } + } + return out; +} + +static inline void cavlRemove(Cavl** const root, const Cavl* const node) +{ + if ((root != NULL) && (node != NULL)) + { + CAVL_ASSERT(*root != NULL); // Otherwise, the node would have to be NULL. + CAVL_ASSERT((node->up != NULL) || (node == *root)); + Cavl* p = NULL; // The lowest parent node that suffered a shortening of its subtree. + bool r = false; // Which side of the above was shortened. + // The first step is to update the topology and remember the node where to start the retracing from later. + // Balancing is not performed yet so we may end up with an unbalanced tree. + if ((node->lr[0] != NULL) && (node->lr[1] != NULL)) + { + Cavl* const re = cavlFindExtremum(node->lr[1], false); + CAVL_ASSERT((re != NULL) && (NULL == re->lr[0]) && (re->up != NULL)); + re->bf = node->bf; + re->lr[0] = node->lr[0]; + re->lr[0]->up = re; + if (re->up != node) + { + p = re->up; // Retracing starts with the ex-parent of our replacement node. + CAVL_ASSERT(p->lr[0] == re); + p->lr[0] = re->lr[1]; // Reducing the height of the left subtree here. + if (p->lr[0] != NULL) + { + p->lr[0]->up = p; + } + re->lr[1] = node->lr[1]; + re->lr[1]->up = re; + r = false; + } + else // In this case, we are reducing the height of the right subtree, so r=1. + { + p = re; // Retracing starts with the replacement node itself as we are deleting its parent. + r = true; // The right child of the replacement node remains the same so we don't bother relinking it. + } + re->up = node->up; + if (re->up != NULL) + { + re->up->lr[re->up->lr[1] == node] = re; // Replace link in the parent of node. + } + else + { + *root = re; + } + } + else // Either or both of the children are NULL. + { + p = node->up; + const bool rr = node->lr[1] != NULL; + if (node->lr[rr] != NULL) + { + node->lr[rr]->up = p; + } + if (p != NULL) + { + r = p->lr[1] == node; + p->lr[r] = node->lr[rr]; + if (p->lr[r] != NULL) + { + p->lr[r]->up = p; + } + } + else + { + *root = node->lr[rr]; + } + } + // Now that the topology is updated, perform the retracing to restore balance. We climb up adjusting the + // balance factors until we reach the root or a parent whose balance factor becomes plus/minus one, which + // means that that parent was able to absorb the balance delta; in other words, the height of the outer + // subtree is unchanged, so upper balance factors shall be kept unchanged. + if (p != NULL) + { + Cavl* c = NULL; + for (;;) + { + c = cavlPrivateAdjustBalance(p, !r); + p = c->up; + if ((c->bf != 0) || (NULL == p)) // Reached the root or the height difference is absorbed by c. + { + break; + } + r = p->lr[1] == c; + } + if (NULL == p) + { + CAVL_ASSERT(c != NULL); + *root = c; + } + } + } +} + +#ifdef __cplusplus +} +#endif \ No newline at end of file diff --git a/components/esp_canard/include/canard.h b/components/esp_canard/include/canard.h new file mode 100644 index 0000000..4cd172e --- /dev/null +++ b/components/esp_canard/include/canard.h @@ -0,0 +1,714 @@ +/// ____ ______ __ __ +/// / __ `____ ___ ____ / ____/_ ______ / /_ ____ / / +/// / / / / __ `/ _ `/ __ `/ / / / / / __ `/ __ `/ __ `/ / +/// / /_/ / /_/ / __/ / / / /___/ /_/ / /_/ / / / / /_/ / / +/// `____/ .___/`___/_/ /_/`____/`__, / .___/_/ /_/`__,_/_/ +/// /_/ /____/_/ +/// +/// Libcanard is a compact implementation of the Cyphal/CAN protocol for high-integrity real-time embedded systems. +/// It is designed for use in robust deterministic embedded systems equipped with at least 32K ROM and 8K RAM. +/// The codebase follows the MISRA C rules, has 100% test coverage, and is validated by at least two static analyzers. +/// The library is designed to be compatible with any target platform and instruction set architecture, from 8 to 64 +/// bit, little- and big-endian, RTOS-based or baremetal, etc., as long as there is a standards-compliant compiler. +/// +/// INTEGRATION +/// +/// The library is intended to be integrated into the end application by simply copying its source files into the +/// source tree of the project; it does not require any special compilation options and should work out of the box. +/// There are build-time configuration parameters defined near the top of canard.c, but they are safe to ignore. +/// +/// As explained in this documentation, the library requires a deterministic constant-time bounded-fragmentation dynamic +/// memory allocator. If your target platform does not provide a deterministic memory manager (most platforms don't), +/// it is recommended to use O1Heap (MIT licensed): https://github.com/pavel-kirienko/o1heap. +/// +/// There are no specific requirements to the underlying I/O layer. Some low-level drivers maintained by the +/// OpenCyphal team may be found at https://github.com/OpenCyphal-Garage/platform_specific_components. +/// +/// If your application requires a MISRA C compliance report, please get in touch with the maintainers via the forum +/// at https://forum.opencyphal.org. +/// +/// ARCHITECTURE +/// +/// Cyphal, as a protocol stack, is composed of two layers: TRANSPORT and PRESENTATION. The transport layer is portable +/// across different transport protocols, one of which is CAN (FD), formally referred to as Cyphal/CAN. This library +/// is focused on Cyphal/CAN only and it will not support other transports. The presentation layer is implemented +/// through the DSDL language and the associated data type regulation policies; these parts are out of the scope of +/// this library as it is focused purely on the transport. +/// +/// This library consists of two components: the transmission (TX) pipeline and the reception (RX) pipeline. +/// The pipelines are completely independent from each other except that they both rely on the same dynamic memory +/// manager. The TX pipeline uses the dynamic memory to store outgoing CAN frames in the prioritized transmission +/// queue. The RX pipeline uses the dynamic memory to store contiguous payload buffers for received transfers and +/// for keeping the transfer reassembly state machine data. The exact memory consumption model is defined for both +/// pipelines, so it is possible to statically determine the minimum size of the dynamic memory pool required to +/// guarantee that a given application will never encounter an out-of-memory error at runtime. +/// +/// Much like with dynamic memory, the time complexity of every API function is well-characterized, allowing the +/// application to guarantee predictable real-time performance. +/// +/// The TX pipeline is managed with the help of four API functions. The first one -- canardTxInit() -- is used for +/// constructing a new TX queue, of which there should be as many as there are redundant CAN interfaces; +/// each queue is managed independently. When the application needs to emit a transfer, it invokes canardTxPush() +/// on each queue separately. The function splits the transfer into CAN frames and stores them into the queue. +/// The application then picks the produced CAN frames from the queue one-by-one by calling canardTxPeek() followed +/// by canardTxPop() -- the former allows the application to look at the next frame scheduled for transmission, +/// and the latter tells the library that the frame shall be removed from the queue. +/// Popped frames need to be manually deallocated by the application upon transmission. +/// +/// The RX pipeline is managed with the help of three API functions; unlike the TX pipeline, there is one shared +/// state for all redundant interfaces that manages deduplication transparently. The main function canardRxAccept() +/// takes a received CAN frame and updates the appropriate transfer reassembly state machine. The functions +/// canardRxSubscribe() and its counterpart canardRxUnsubscribe() instruct the library which transfers should be +/// received (by default, all transfers are ignored); also, the subscription function specifies vital transfer +/// reassembly parameters such as the maximum payload size (i.e., the maximum size of a serialized representation +/// of a DSDL object) and the transfer-ID timeout. Transfers that carry more payload than the configured maximum per +/// subscription are truncated following the Implicit Truncation Rule (ITR) defined by the Cyphal Specification -- +/// the rule is implemented to facilitate backward-compatible DSDL data type extensibility. +/// +/// The library supports a practically unlimited number of redundant interfaces. +/// +/// The library is not thread-safe: if used in a concurrent environment, it is the responsibility of the application +/// to provide adequate synchronization. +/// +/// The library is purely reactive: it does not perform any background processing and does not require periodic +/// servicing. Its internal state is only updated as a response to well-specified external events. +/// +/// -------------------------------------------------------------------------------------------------------------------- +/// +/// This software is distributed under the terms of the MIT License. +/// Copyright (c) 2016 OpenCyphal. +/// Author: Pavel Kirienko +/// Contributors: https://github.com/OpenCyphal/libcanard/contributors. + +#ifndef CANARD_H_INCLUDED +#define CANARD_H_INCLUDED + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/// Semantic version of this library (not the Cyphal specification). +/// API will be backward compatible within the same major version. +#define CANARD_VERSION_MAJOR 3 +#define CANARD_VERSION_MINOR 2 + +/// The version number of the Cyphal specification implemented by this library. +#define CANARD_CYPHAL_SPECIFICATION_VERSION_MAJOR 1 +#define CANARD_CYPHAL_SPECIFICATION_VERSION_MINOR 0 + +/// These error codes may be returned from the library API calls whose return type is a signed integer in the negated +/// form (e.g., error code 2 returned as -2). A non-negative return value represents success. +/// API calls whose return type is not a signed integer cannot fail by contract. +/// No other error states may occur in the library. +/// By contract, a well-characterized application with a properly sized memory pool will never encounter errors. +/// The error code 1 is not used because -1 is often used as a generic error code in 3rd-party code. +#define CANARD_ERROR_INVALID_ARGUMENT 2 +#define CANARD_ERROR_OUT_OF_MEMORY 3 + +/// MTU values for the supported protocols. +/// Per the recommendations given in the Cyphal/CAN Specification, other MTU values should not be used. +#define CANARD_MTU_CAN_CLASSIC 8U +#define CANARD_MTU_CAN_FD 64U +#define CANARD_MTU_MAX CANARD_MTU_CAN_FD + +/// Parameter ranges are inclusive; the lower bound is zero for all. See Cyphal/CAN Specification for background. +#define CANARD_SUBJECT_ID_MAX 8191U +#define CANARD_SERVICE_ID_MAX 511U +#define CANARD_NODE_ID_MAX 127U +#define CANARD_PRIORITY_MAX 7U +#define CANARD_TRANSFER_ID_BIT_LENGTH 5U +#define CANARD_TRANSFER_ID_MAX ((1U << CANARD_TRANSFER_ID_BIT_LENGTH) - 1U) + +/// This value represents an undefined node-ID: broadcast destination or anonymous source. +/// Library functions treat all values above CANARD_NODE_ID_MAX as anonymous. +#define CANARD_NODE_ID_UNSET 255U + +/// This is the recommended transfer-ID timeout value given in the Cyphal Specification. The application may choose +/// different values per subscription (i.e., per data specifier) depending on its timing requirements. +#define CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC 2000000UL + +// Forward declarations. +typedef struct CanardInstance CanardInstance; +typedef struct CanardTreeNode CanardTreeNode; +typedef struct CanardTxQueueItem CanardTxQueueItem; +typedef uint64_t CanardMicrosecond; +typedef uint16_t CanardPortID; +typedef uint8_t CanardNodeID; +typedef uint8_t CanardTransferID; + +/// Transfer priority level mnemonics per the recommendations given in the Cyphal Specification. +typedef enum +{ + CanardPriorityExceptional = 0, + CanardPriorityImmediate = 1, + CanardPriorityFast = 2, + CanardPriorityHigh = 3, + CanardPriorityNominal = 4, ///< Nominal priority level should be the default. + CanardPriorityLow = 5, + CanardPrioritySlow = 6, + CanardPriorityOptional = 7, +} CanardPriority; + +/// Transfer kinds as defined by the Cyphal Specification. +typedef enum +{ + CanardTransferKindMessage = 0, ///< Multicast, from publisher to all subscribers. + CanardTransferKindResponse = 1, ///< Point-to-point, from server to client. + CanardTransferKindRequest = 2, ///< Point-to-point, from client to server. +} CanardTransferKind; +#define CANARD_NUM_TRANSFER_KINDS 3 + +/// The AVL tree node structure is exposed here to avoid pointer casting/arithmetics inside the library. +/// The user code is not expected to interact with this type except if advanced introspection is required. +struct CanardTreeNode +{ + CanardTreeNode* up; ///< Do not access this field. + CanardTreeNode* lr[2]; ///< Left and right children of this node may be accessed for tree traversal. + int8_t bf; ///< Do not access this field. +}; + +/// CAN data frame with an extended 29-bit ID. RTR/Error frames are not used and therefore not modeled here. +/// CAN frames with 11-bit ID are not used by Cyphal/CAN and so they are not supported by the library. +typedef struct +{ + /// 29-bit extended ID. The bits above 29-th shall be zero. + uint32_t extended_can_id; + + /// The useful data in the frame. The length value is not to be confused with DLC! + /// If the payload is empty (payload_size = 0), the payload pointer may be NULL. + /// For RX frames: the library does not expect the lifetime of the pointee to extend beyond the point of return + /// from the API function. That is, the pointee can be invalidated immediately after the frame has been processed. + /// For TX frames: the frame and the payload are allocated within the same dynamic memory fragment, so their + /// lifetimes are identical; when the frame is freed, the payload is invalidated. + /// A more detailed overview of the dataflow and related resource management issues is provided in the API docs. + size_t payload_size; + const void* payload; +} CanardFrame; + +/// Conversion look-up table from CAN DLC to data length. +extern const uint8_t CanardCANDLCToLength[16]; + +/// Conversion look-up table from data length to CAN DLC; the length is rounded up. +extern const uint8_t CanardCANLengthToDLC[65]; + +/// A Cyphal transfer metadata (everything except the payload). +/// Per Specification, a transfer is represented on the wire as a non-empty set of transport frames (i.e., CAN frames). +/// The library is responsible for serializing transfers into transport frames when transmitting, and reassembling +/// transfers from an incoming stream of frames (possibly duplicated if redundant interfaces are used) during reception. +typedef struct +{ + /// Per the Specification, all frames belonging to a given transfer shall share the same priority level. + /// If this is not the case, then this field contains the priority level of the last frame to arrive. + CanardPriority priority; + + CanardTransferKind transfer_kind; + + /// Subject-ID for message publications; service-ID for service requests/responses. + CanardPortID port_id; + + /// For outgoing message transfers the value shall be CANARD_NODE_ID_UNSET (otherwise the state is invalid). + /// For outgoing service transfers this is the destination address (invalid if unset). + /// For incoming non-anonymous transfers this is the node-ID of the origin. + /// For incoming anonymous transfers the value is reported as CANARD_NODE_ID_UNSET. + CanardNodeID remote_node_id; + + /// When responding to a service request, the response transfer SHALL have the same transfer-ID value as the + /// request because the client will match the response with the request based on that. + /// + /// When publishing a message transfer, the value SHALL be one greater than the previous transfer under the same + /// subject-ID; the initial value should be zero. + /// + /// When publishing a service request transfer, the value SHALL be one greater than the previous transfer under + /// the same service-ID addressed to the same server node-ID; the initial value should be zero. + /// + /// Upon overflow, the value SHALL be reset back to zero. + /// Values above CANARD_TRANSFER_ID_MAX are permitted -- the library will compute the modulo automatically. + /// For received transfers, the values never exceed CANARD_TRANSFER_ID_MAX. + /// + /// A simple and robust way of managing transfer-ID counters is to keep a separate static variable per subject-ID + /// and per (service-ID, server-node-ID) pair. + CanardTransferID transfer_id; +} CanardTransferMetadata; + +/// Prioritized transmission queue that keeps CAN frames destined for transmission via one CAN interface. +/// Applications with redundant interfaces are expected to have one instance of this type per interface. +/// Applications that are not interested in transmission may have zero queues. +/// All operations (push, peek, pop) are O(log n); there is exactly one heap allocation per element. +/// API functions that work with this type are named "canardTx*()", find them below. +typedef struct CanardTxQueue +{ + /// The maximum number of frames this queue is allowed to contain. An attempt to push more will fail with an + /// out-of-memory error even if the memory is not exhausted. This value can be changed by the user at any moment. + /// The purpose of this limitation is to ensure that a blocked queue does not exhaust the heap memory. + size_t capacity; + + /// The transport-layer maximum transmission unit (MTU). The value can be changed arbitrarily at any time between + /// pushes. It defines the maximum number of data bytes per CAN data frame in outgoing transfers via this queue. + /// + /// Only the standard values should be used as recommended by the specification; + /// otherwise, networking interoperability issues may arise. See recommended values CANARD_MTU_*. + /// + /// Valid values are any valid CAN frame data length value not smaller than 8. + /// Invalid values are treated as the nearest valid value. The default is the maximum valid value. + size_t mtu_bytes; + + /// The number of frames that are currently contained in the queue, initially zero. + /// Do not modify this field! + size_t size; + + /// The root of the priority queue is NULL if the queue is empty. Do not modify this field! + CanardTreeNode* root; + + /// This field can be arbitrarily mutated by the user. It is never accessed by the library. + /// Its purpose is to simplify integration with OOP interfaces. + void* user_reference; +} CanardTxQueue; + +/// One frame stored in the transmission queue along with its metadata. +struct CanardTxQueueItem +{ + /// Internal use only; do not access this field. + CanardTreeNode base; + + /// Points to the next frame in this transfer or NULL. This field is mostly intended for own needs of the library. + /// Normally, the application would not use it because transfer frame ordering is orthogonal to global TX ordering. + /// It can be useful though for pulling pending frames from the TX queue if at least one frame of their transfer + /// failed to transmit; the idea is that if at least one frame is missing, the transfer will not be received by + /// remote nodes anyway, so all its remaining frames can be dropped from the queue at once using canardTxPop(). + CanardTxQueueItem* next_in_transfer; + + /// This is the same value that is passed to canardTxPush(). + /// Frames whose transmission deadline is in the past shall be dropped. + CanardMicrosecond tx_deadline_usec; + + /// The actual CAN frame data. + CanardFrame frame; +}; + +/// Transfer subscription state. The application can register its interest in a particular kind of data exchanged +/// over the bus by creating such subscription objects. Frames that carry data for which there is no active +/// subscription will be silently dropped by the library. The entire RX pipeline is invariant to the number of +/// redundant CAN interfaces used. +/// +/// SUBSCRIPTION INSTANCES SHALL NOT BE MOVED WHILE IN USE. +/// +/// The memory footprint of a subscription is large. On a 32-bit platform it slightly exceeds half a KiB. +/// This is an intentional time-memory trade-off: use a large look-up table to ensure predictable temporal properties. +typedef struct CanardRxSubscription +{ + CanardTreeNode base; ///< Read-only DO NOT MODIFY THIS + + CanardMicrosecond transfer_id_timeout_usec; + size_t extent; ///< Read-only DO NOT MODIFY THIS + CanardPortID port_id; ///< Read-only DO NOT MODIFY THIS + + /// This field can be arbitrarily mutated by the user. It is never accessed by the library. + /// Its purpose is to simplify integration with OOP interfaces. + void* user_reference; + + /// The current architecture is an acceptable middle ground between worst-case execution time and memory + /// consumption. Instead of statically pre-allocating a dedicated RX session for each remote node-ID here in + /// this table, we only keep pointers, which are NULL by default, populating a new RX session dynamically + /// on an ad-hoc basis when we first receive a transfer from that node. This is O(1) because our memory + /// allocation routines are assumed to be O(1) and we make at most one allocation per remote node. + /// + /// A more predictable and simpler approach is to pre-allocate states here statically instead of keeping + /// just pointers, but it would push the size of this instance from about 0.5 KiB to ~3 KiB for a typical 32-bit + /// system. Since this is a general-purpose library, we have to pick a middle ground so we use the more complex + /// but more memory-efficient approach. + struct CanardInternalRxSession* sessions[CANARD_NODE_ID_MAX + 1U]; ///< Read-only DO NOT MODIFY THIS +} CanardRxSubscription; + +/// Reassembled incoming transfer returned by canardRxAccept(). +typedef struct CanardRxTransfer +{ + CanardTransferMetadata metadata; + + /// The timestamp of the first received CAN frame of this transfer. + /// The time system may be arbitrary as long as the clock is monotonic (steady). + CanardMicrosecond timestamp_usec; + + /// If the payload is empty (payload_size = 0), the payload pointer may be NULL. + /// The application is required to deallocate the payload buffer after the transfer is processed. + size_t payload_size; + void* payload; +} CanardRxTransfer; + +/// A pointer to the memory allocation function. The semantics are similar to malloc(): +/// - The returned pointer shall point to an uninitialized block of memory that is at least "amount" bytes large. +/// - If there is not enough memory, the returned pointer shall be NULL. +/// - The memory shall be aligned at least at max_align_t. +/// - The execution time should be constant (O(1)). +/// - The worst-case memory fragmentation should be bounded and easily predictable. +/// If the standard dynamic memory manager of the target platform does not satisfy the above requirements, +/// consider using O1Heap: https://github.com/pavel-kirienko/o1heap. +typedef void* (*CanardMemoryAllocate)(CanardInstance* ins, size_t amount); + +/// The counterpart of the above -- this function is invoked to return previously allocated memory to the allocator. +/// The semantics are similar to free(): +/// - The pointer was previously returned by the allocation function. +/// - The pointer may be NULL, in which case the function shall have no effect. +/// - The execution time should be constant (O(1)). +typedef void (*CanardMemoryFree)(CanardInstance* ins, void* pointer); + +/// This is the core structure that keeps all of the states and allocated resources of the library instance. +struct CanardInstance +{ + /// User pointer that can link this instance with other objects. + /// This field can be changed arbitrarily, the library does not access it after initialization. + /// The default value is NULL. + void* user_reference; + + /// The node-ID of the local node. + /// Per the Cyphal Specification, the node-ID should not be assigned more than once. + /// Invalid values are treated as CANARD_NODE_ID_UNSET. The default value is CANARD_NODE_ID_UNSET. + CanardNodeID node_id; + + /// Dynamic memory management callbacks. See their type documentation for details. + /// They SHALL be valid function pointers at all times. + /// The time complexity models given in the API documentation are made on the assumption that the memory management + /// functions have constant complexity O(1). + /// + /// The following API functions may allocate memory: canardRxAccept(), canardTxPush(). + /// The following API functions may deallocate memory: canardRxAccept(), canardRxSubscribe(), canardRxUnsubscribe(). + /// The exact memory requirement and usage model is specified for each function in its documentation. + CanardMemoryAllocate memory_allocate; + CanardMemoryFree memory_free; + + /// Read-only DO NOT MODIFY THIS + CanardTreeNode* rx_subscriptions[CANARD_NUM_TRANSFER_KINDS]; +}; + +/// CAN acceptance filter configuration with an extended 29-bit ID utilizing an ID + mask filter scheme. +/// Filter configuration can be programmed into a CAN controller to filter out irrelevant messages in hardware. +/// This allows the software application to reduce CPU load spent on processing irrelevant messages. +typedef struct CanardFilter +{ + /// 29-bit extended ID. Defines the extended CAN ID to filter incoming frames against. + /// The bits above 29-th shall be zero. + uint32_t extended_can_id; + /// 29-bit extended mask. Defines the bitmask used to enable/disable bits used to filter messages. + /// Only bits that are enabled are compared to the extended_can_id for filtering. + /// The bits above 29-th shall be zero. + uint32_t extended_mask; +} CanardFilter; + +/// Construct a new library instance. +/// The default values will be assigned as specified in the structure field documentation. +/// If any of the pointers are NULL, the behavior is undefined. +/// +/// The instance does not hold any resources itself except for the allocated memory. +/// To safely discard it, simply remove all existing subscriptions, and don't forget about the TX queues. +/// +/// The time complexity is constant. This function does not invoke the dynamic memory manager. +CanardInstance canardInit(const CanardMemoryAllocate memory_allocate, const CanardMemoryFree memory_free); + +/// Construct a new transmission queue instance with the specified values for capacity and mtu_bytes. +/// No memory allocation is going to take place until the queue is actually pushed to. +/// Applications are expected to have one instance of this type per redundant interface. +/// +/// The instance does not hold any resources itself except for the allocated memory. +/// To safely discard it, simply pop all items from the queue. +/// +/// The time complexity is constant. This function does not invoke the dynamic memory manager. +CanardTxQueue canardTxInit(const size_t capacity, const size_t mtu_bytes); + +/// This function serializes a transfer into a sequence of transport frames and inserts them into the prioritized +/// transmission queue at the appropriate position. Afterwards, the application is supposed to take the enqueued frames +/// from the transmission queue using the function canardTxPeek() and transmit them. Each transmitted (or otherwise +/// discarded, e.g., due to timeout) frame should be removed from the queue using canardTxPop(). The queue is +/// prioritized following the normal CAN frame arbitration rules to avoid the inner priority inversion. The transfer +/// payload will be copied into the transmission queue so that the lifetime of the frames is not related to the +/// lifetime of the input payload buffer. +/// +/// The MTU of the generated frames is dependent on the value of the MTU setting at the time when this function +/// is invoked. The MTU setting can be changed arbitrarily between invocations. +/// +/// The tx_deadline_usec will be used to populate the timestamp values of the resulting transport +/// frames (so all frames will have the same timestamp value). This feature is intended to facilitate transmission +/// deadline tracking, i.e., aborting frames that could not be transmitted before the specified deadline. +/// Therefore, normally, the timestamp value should be in the future. +/// The library itself, however, does not use or check this value in any way, so it can be zero if not needed. +/// +/// The function returns the number of frames enqueued into the prioritized TX queue (which is always a positive +/// number) in case of success (so that the application can track the number of items in the TX queue if necessary). +/// In case of failure, the function returns a negated error code: either invalid argument or out-of-memory. +/// +/// An invalid argument error may be returned in the following cases: +/// - Any of the input arguments are NULL. +/// - The remote node-ID is not CANARD_NODE_ID_UNSET and the transfer is a message transfer. +/// - The remote node-ID is above CANARD_NODE_ID_MAX and the transfer is a service transfer. +/// - The priority, subject-ID, or service-ID exceed their respective maximums. +/// - The transfer kind is invalid. +/// - The payload pointer is NULL while the payload size is nonzero. +/// - The local node is anonymous and a message transfer is requested that requires a multi-frame transfer. +/// - The local node is anonymous and a service transfer is requested. +/// The following cases are handled without raising an invalid argument error: +/// - If the transfer-ID is above the maximum, the excessive bits are silently masked away +/// (i.e., the modulo is computed automatically, so the caller doesn't have to bother). +/// +/// An out-of-memory error is returned if a TX frame could not be allocated due to the memory being exhausted, +/// or if the capacity of the queue would be exhausted by this operation. In such cases, all frames allocated for +/// this transfer (if any) will be deallocated automatically. In other words, either all frames of the transfer are +/// enqueued successfully, or none are. +/// +/// The time complexity is O(p + log e), where p is the amount of payload in the transfer, and e is the number of +/// frames already enqueued in the transmission queue. +/// +/// The memory allocation requirement is one allocation per transport frame. A single-frame transfer takes one +/// allocation; a multi-frame transfer of N frames takes N allocations. The size of each allocation is +/// (sizeof(CanardTxQueueItem) + MTU). +int32_t canardTxPush(CanardTxQueue* const que, + CanardInstance* const ins, + const CanardMicrosecond tx_deadline_usec, + const CanardTransferMetadata* const metadata, + const size_t payload_size, + const void* const payload); + +/// This function accesses the top element of the prioritized transmission queue. The queue itself is not modified +/// (i.e., the accessed element is not removed). The application should invoke this function to collect the transport +/// frames of serialized transfers pushed into the prioritized transmission queue by canardTxPush(). +/// +/// The timestamp values of returned frames are initialized with tx_deadline_usec from canardTxPush(). +/// Timestamps are used to specify the transmission deadline. It is up to the application and/or the media layer +/// to implement the discardment of timed-out transport frames. The library does not check it, so a frame that is +/// already timed out may be returned here. +/// +/// If the queue is empty or if the argument is NULL, the returned value is NULL. +/// +/// If the queue is non-empty, the returned value is a pointer to its top element (i.e., the next frame to transmit). +/// The returned pointer points to an object allocated in the dynamic storage; it should be eventually freed by the +/// application by calling CanardInstance::memory_free(). The memory shall not be freed before the entry is removed +/// from the queue by calling canardTxPop(); this is because until canardTxPop() is executed, the library retains +/// ownership of the object. The pointer retains validity until explicitly freed by the application; in other words, +/// calling canardTxPop() does not invalidate the object. +/// +/// The payload buffer is located shortly after the object itself, in the same memory fragment. The application shall +/// not attempt to free it. +/// +/// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager. +const CanardTxQueueItem* canardTxPeek(const CanardTxQueue* const que); + +/// This function transfers the ownership of the specified element of the prioritized transmission queue from the queue +/// to the application. The element does not necessarily need to be the top one -- it is safe to dequeue any element. +/// The element is dequeued but not invalidated; it is the responsibility of the application to deallocate the +/// memory used by the object later. The memory SHALL NOT be deallocated UNTIL this function is invoked. +/// The function returns the same pointer that it is given except that it becomes mutable. +/// +/// If any of the arguments are NULL, the function has no effect and returns NULL. +/// +/// The time complexity is logarithmic of the queue size. This function does not invoke the dynamic memory manager. +CanardTxQueueItem* canardTxPop(CanardTxQueue* const que, const CanardTxQueueItem* const item); + +/// This function implements the transfer reassembly logic. It accepts a transport frame from any of the redundant +/// interfaces, locates the appropriate subscription state, and, if found, updates it. If the frame completed a +/// transfer, the return value is 1 (one) and the out_transfer pointer is populated with the parameters of the +/// newly reassembled transfer. The transfer reassembly logic is defined in the Cyphal specification. +/// +/// The MTU of the accepted frame can be arbitrary; that is, any MTU is accepted. The DLC validity is irrelevant. +/// +/// Any value of redundant_iface_index is accepted; that is, up to 256 redundant interfaces are supported. +/// The index of the interface from which the transfer is accepted is always the same as redundant_iface_index +/// of the current invocation, so the application can always determine which interface has delivered the transfer. +/// +/// Upon return, the out_subscription pointer will point to the instance of CanardRxSubscription that accepted this +/// frame; if no matching subscription exists (i.e., frame discarded), the pointer will be NULL. +/// If this information is not relevant, set out_subscription to NULL. +/// The purpose of this argument is to allow integration with OOP adapters built on top of libcanard; see also the +/// user_reference provided in CanardRxSubscription. +/// +/// The function invokes the dynamic memory manager in the following cases only: +/// +/// 1. New memory for a session state object is allocated when a new session is initiated. +/// This event occurs when a transport frame that matches a known subscription is received from a node that +/// did not emit matching frames since the subscription was created. +/// Once a new session is created, it is not destroyed until the subscription is terminated by invoking +/// canardRxUnsubscribe(). The number of sessions is bounded and the bound is low (at most the number of nodes +/// in the network minus one), also the size of a session instance is very small, so the removal is unnecessary. +/// Real-time networks typically do not change their configuration at runtime, so it is possible to reduce +/// the time complexity by never deallocating sessions. +/// The size of a session instance is at most 48 bytes on any conventional platform (typically much smaller). +/// +/// 2. New memory for the transfer payload buffer is allocated when a new transfer is initiated, unless the buffer +/// was already allocated at the time. +/// This event occurs when a transport frame that matches a known subscription is received and it begins a +/// new transfer (that is, the start-of-frame flag is set and it is not a duplicate). +/// The amount of the allocated memory equals the extent as configured via canardRxSubscribe(); please read +/// its documentation for further information about the extent and related edge cases. +/// The worst case occurs when every node on the bus initiates a multi-frame transfer for which there is a +/// matching subscription: in this case, the library will allocate number_of_nodes allocations, where each +/// allocation is the same size as the configured extent. +/// +/// 3. Memory allocated for the transfer payload buffer may be deallocated at the discretion of the library. +/// This operation does not increase the worst case execution time and does not improve the worst case memory +/// consumption, so a deterministic application need not consider this behavior in the resource analysis. +/// This behavior is implemented for the benefit of applications where rigorous characterization is unnecessary. +/// +/// The worst case dynamic memory consumption per subscription is: +/// +/// (sizeof(session instance) + extent) * number_of_nodes +/// +/// Where sizeof(session instance) and extent are defined above, and number_of_nodes is the number of remote +/// nodes emitting transfers that match the subscription (which cannot exceed (CANARD_NODE_ID_MAX-1) by design). +/// If the dynamic memory pool is sized correctly, the application is guaranteed to never encounter an +/// out-of-memory (OOM) error at runtime. The actual size of the dynamic memory pool is typically larger; +/// for a detailed treatment of the problem and the related theory please refer to the documentation of O1Heap -- +/// a deterministic memory allocator for hard real-time embedded systems. +/// +/// The time complexity is O(p + log n) where n is the number of subject-IDs or service-IDs subscribed to by the +/// application, depending on the transfer kind of the supplied frame, and p is the amount of payload in the received +/// frame (because it will be copied into an internal contiguous buffer). Observe that the time complexity is +/// invariant to the network configuration (such as the number of online nodes) -- this is a very important +/// design guarantee for real-time applications because the execution time is dependent only on the number of +/// active subscriptions for a given transfer kind, and the MTU, both of which are easy to predict and account for. +/// Excepting the subscription search and the payload data copying, the entire RX pipeline contains neither loops +/// nor recursion. +/// Misaddressed and malformed frames are discarded in constant time. +/// +/// The function returns 1 (one) if the new frame completed a transfer. In this case, the details of the transfer +/// are stored into out_transfer, and the transfer payload buffer ownership is passed to that object. The lifetime +/// of the resulting transfer object is not related to the lifetime of the input transport frame (that is, even if +/// it is a single-frame transfer, its payload is copied out into a new dynamically allocated buffer storage). +/// If the extent is zero, the payload pointer may be NULL, since there is no data to store and so a +/// buffer is not needed. The application is responsible for deallocating the payload buffer when the processing +/// is done by invoking memory_free on the transfer payload pointer. +/// +/// The function returns a negated out-of-memory error if it was unable to allocate dynamic memory. +/// +/// The function does nothing and returns a negated invalid argument error immediately if any condition is true: +/// - Any of the input arguments that are pointers are NULL. +/// - The payload pointer of the input frame is NULL while its size is non-zero. +/// - The CAN ID of the input frame is not less than 2**29=0x20000000. +/// +/// The function returns zero if any of the following conditions are true (the general policy is that protocol +/// errors are not escalated because they do not construe a node-local error): +/// - The received frame is not a valid Cyphal/CAN transport frame. +/// - The received frame is a valid Cyphal/CAN transport frame, but there is no matching subscription, +/// the frame did not complete a transfer, the frame forms an invalid frame sequence, the frame is a duplicate, +/// the frame is unicast to a different node (address mismatch). +int8_t canardRxAccept(CanardInstance* const ins, + const CanardMicrosecond timestamp_usec, + const CanardFrame* const frame, + const uint8_t redundant_iface_index, + CanardRxTransfer* const out_transfer, + CanardRxSubscription** const out_subscription); + +/// This function creates a new subscription, allowing the application to register its interest in a particular +/// category of transfers. The library will reject all transport frames for which there is no active subscription. +/// The reference out_subscription shall retain validity until the subscription is terminated (the referred object +/// cannot be moved or destroyed). +/// +/// If such subscription already exists, it will be removed first as if canardRxUnsubscribe() was +/// invoked by the application, and then re-created anew with the new parameters. +/// +/// The extent defines the size of the transfer payload memory buffer; or, in other words, the maximum possible size +/// of received objects, considering also possible future versions with new fields. It is safe to pick larger values. +/// Note well that the extent is not the same thing as the maximum size of the object, it is usually larger! +/// Transfers that carry payloads that exceed the specified extent will be accepted anyway but the excess payload +/// will be truncated away, as mandated by the Specification. The transfer CRC is always validated regardless of +/// whether its payload is truncated. +/// +/// The default transfer-ID timeout value is defined as CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC; use it if not sure. +/// The redundant interface fail-over timeout (if redundant interfaces are used) is the same as the transfer-ID timeout. +/// It may be reduced in a future release of the library, but it will not affect the backward compatibility. +/// +/// The return value is 1 if a new subscription has been created as requested. +/// The return value is 0 if such subscription existed at the time the function was invoked. In this case, +/// the existing subscription is terminated and then a new one is created in its place. Pending transfers may be lost. +/// The return value is a negated invalid argument error if any of the input arguments are invalid. +/// +/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. +/// This function does not allocate new memory. The function may deallocate memory if such subscription already +/// existed; the deallocation behavior is specified in the documentation for canardRxUnsubscribe(). +/// +/// Subscription instances have large look-up tables to ensure that the temporal properties of the algorithms are +/// invariant to the network configuration (i.e., a node that is validated on a network containing one other node +/// will provably perform identically on a network that contains X nodes). This is a conscious time-memory trade-off. +int8_t canardRxSubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id, + const size_t extent, + const CanardMicrosecond transfer_id_timeout_usec, + CanardRxSubscription* const out_subscription); + +/// This function reverses the effect of canardRxSubscribe(). +/// If the subscription is found, all its memory is de-allocated (session states and payload buffers); to determine +/// the amount of memory freed, please refer to the memory allocation requirement model of canardRxAccept(). +/// +/// The return value is 1 if such subscription existed (and, therefore, it was removed). +/// The return value is 0 if such subscription does not exist. In this case, the function has no effect. +/// The return value is a negated invalid argument error if any of the input arguments are invalid. +/// +/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. +/// This function does not allocate new memory. +int8_t canardRxUnsubscribe(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id); + +/// This function allows to check the effect of canardRxSubscribe() and canardRxUnsubscribe(). +/// +/// The return value is 1 if the specified subscription exists, 0 otherwise. +/// The return value is a negated invalid argument error if any of the input arguments are invalid. +/// Output out_subscription could be NULL, but if it is not, it will be populated with the pointer to the existing +/// subscription. In case the subscription does not exist (or error), out_subscription won't be touched. +/// Result pointer to the subscription is valid until the subscription is terminated. +/// +/// The time complexity is logarithmic from the number of current subscriptions under the specified transfer kind. +/// This function does not allocate new memory. +int8_t canardRxGetSubscription(CanardInstance* const ins, + const CanardTransferKind transfer_kind, + const CanardPortID port_id, + CanardRxSubscription** const out_subscription); + +/// Utilities for generating CAN controller hardware acceptance filter configurations +/// to accept specific subjects, services, or nodes. +/// +/// Complex applications will likely subscribe to more subject IDs than there are +/// acceptance filters available in the CAN hardware. In this case, the application +/// should implement filter consolidation. See canardConsolidateFilters() +/// as well as the Cyphal specification for details. + +/// Generate an acceptance filter configuration to accept a specific subject ID. +CanardFilter canardMakeFilterForSubject(const CanardPortID subject_id); + +/// Generate an acceptance filter configuration to accept both requests and responses for a specific service. +/// +/// Users may prefer to instead use a catch-all acceptance filter configuration for accepting +/// all service requests and responses targeted at the specified local node ID. +/// See canardMakeFilterForServices() for this. +CanardFilter canardMakeFilterForService(const CanardPortID service_id, const CanardNodeID local_node_id); + +/// Generate an acceptance filter configuration to accept all service +/// requests and responses targeted to the specified local node ID. +/// +/// Due to the relatively low frequency of service transfers expected on a network, +/// and the fact that a service directed at a specific node is not likely to be rejected by that node, +/// a user may prefer to use this over canardMakeFilterForService() +/// in order to simplify the API usage and reduce the number of required hardware CAN acceptance filters. +CanardFilter canardMakeFilterForServices(const CanardNodeID local_node_id); + +/// Consolidate two acceptance filter configurations into a single configuration. +/// +/// Complex applications will likely subscribe to more subject IDs than there are +/// acceptance filters available in the CAN hardware. In this case, the application +/// should implement filter consolidation. While this may make it impossible to create +/// a 'perfect' filter that only accepts desired subject IDs, the application should apply +/// consolidation in a manner that minimizes the number of undesired messages that pass +/// through the hardware acceptance filters and require software filtering (implemented by canardRxSubscribe). +/// +/// While optimal choice of filter consolidation is a function of the number of available hardware filters, +/// the set of transfers needed by the application, and the expected frequency of occurrence +/// of all possible distinct transfers on the bus, it is possible to generate a quasi-optimal configuration +/// if information about the frequency of occurrence of different transfers is not known. +/// For details, see the "Automatic hardware acceptance filter configuration" note under the Cyphal/CAN section +/// in the Transport Layer chapter of the Cyphal specification. +CanardFilter canardConsolidateFilters(const CanardFilter* const a, const CanardFilter* const b); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/components/esp_nunavut/CMakeLists.txt b/components/esp_nunavut/CMakeLists.txt new file mode 100644 index 0000000..6eb1c36 --- /dev/null +++ b/components/esp_nunavut/CMakeLists.txt @@ -0,0 +1,3 @@ +idf_component_register( + INCLUDE_DIRS "nunavut" +) \ No newline at end of file diff --git a/components/esp_nunavut/nunavut/nunavut/support/serialization.h b/components/esp_nunavut/nunavut/nunavut/support/serialization.h new file mode 100644 index 0000000..f657683 --- /dev/null +++ b/components/esp_nunavut/nunavut/nunavut/support/serialization.h @@ -0,0 +1,585 @@ +// OpenCyphal common serialization support routines. - +// This file is based on canard_dsdl.h, which is part of Libcanard. | C/- +// - +// AUTOGENERATED, DO NOT EDIT. +// +//--------------------------------------------------------------------------------------------------------------------- +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef NUNAVUT_SUPPORT_SERIALIZATION_H_INCLUDED +#define NUNAVUT_SUPPORT_SERIALIZATION_H_INCLUDED + +#ifdef __cplusplus +# if (__cplusplus < 201402L) +# error "Unsupported language: ISO C11, C++14, or a newer version of either is required." +# endif +extern "C" +{ +#else +# if !defined(__STDC_VERSION__) || (__STDC_VERSION__ < 201112L) +# error "Unsupported language: ISO C11 or a newer version is required." +# endif +#endif + +#include + +#include +#include // For isfinite(). +#include +#include +#include // For static_assert (C11) and assert() if NUNAVUT_ASSERT is used. + +static_assert(sizeof(size_t) >= sizeof(size_t), + "The bit-length type used by Nunavut, size_t, " + "is smaller than this platform's size_t type. " + "Nunavut serialization relies on size_t to size_t conversions " + "that do not lose data. You will need to regenerate Nunavut serialization support with a larger " + "unsigned_bit_length type specified."); + +#define NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS 1693710260 +#define NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT 0 +#define NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS 0 +#define NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY 0 +#define NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT 2368206204 + +/// Nunavut returns 0 for success and < 0 for any failure. It is always adequate to check that error_value < 0 +/// to detect errors or error_value == 0 for success. +/// +/// Nunavut serialization will never define more than 127 errors and the reserved error numbers are [-1,-127] +/// (-128 is not used). Error code 1 is currently also not used to avoid conflicts with 3rd-party software. +/// +/// Return values > 0 for Nunavut serialization are undefined. +#define NUNAVUT_SUCCESS 0 +// API usage errors: +#define NUNAVUT_ERROR_INVALID_ARGUMENT 2 +#define NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL 3 +// Invalid representation (caused by bad input data, not API misuse): +#define NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH 10 +#define NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG 11 +#define NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER 12 + +/// Detect whether the target platform is compatible with IEEE 754. +#define NUNAVUT_PLATFORM_IEEE754_FLOAT \ + ((FLT_RADIX == 2) && (FLT_MANT_DIG == 24) && (FLT_MIN_EXP == -125) && (FLT_MAX_EXP == 128)) +#define NUNAVUT_PLATFORM_IEEE754_DOUBLE \ + ((FLT_RADIX == 2) && (DBL_MANT_DIG == 53) && (DBL_MIN_EXP == -1021) && (DBL_MAX_EXP == 1024)) + +// This code is endianness-invariant. Use target_endianness='little' to generate little-endian-optimized code. + +// ---------------------------------------------------- HELPERS ---------------------------------------------------- + +/// Returns the smallest value. +static inline size_t nunavutChooseMin(const size_t a, const size_t b) +{ + return (a < b) ? a : b; +} + +/// Calculate the number of bits to safely copy from/to a serialized buffer. +/// Mind the units! By convention, buffer size is specified in bytes, but fragment length and offset are in bits. +/// +/// buffer buffer +/// origin end +/// [------------------------- buffer_size_bytes ------------------------] +/// [--------------- fragment_offset_bits ---------------][--- fragment_length_bits ---] +/// [-- out bits --] +/// +static inline size_t nunavutSaturateBufferFragmentBitLength( + const size_t buffer_size_bytes, const size_t fragment_offset_bits, const size_t fragment_length_bits) +{ + const size_t size_bits = (size_t)buffer_size_bytes * 8U; + const size_t tail_bits = size_bits - nunavutChooseMin(size_bits, fragment_offset_bits); + return nunavutChooseMin(fragment_length_bits, tail_bits); +} + +// ---------------------------------------------------- BIT ARRAY ---------------------------------------------------- + +/// Copy the specified number of bits from the source buffer into the destination buffer in accordance with the +/// DSDL bit-level serialization specification. The offsets may be arbitrary (may exceed 8 bits). +/// If both offsets are byte-aligned, the function invokes memmove() and possibly adjusts the last byte separately. +/// If the source and the destination overlap AND the offsets are not byte-aligned, the behavior is undefined. +/// If either source or destination pointers are NULL, the behavior is undefined. +/// Arguments: +/// dst Destination buffer. Shall be at least ceil(length_bits/8) bytes large. +/// dst_offset_bits Offset in bits from the destination pointer. May exceed 8. +/// length_bits The number of bits to copy. Both source and destination shall be large enough. +/// src Source buffer. Shall be at least ceil(length_bits/8) bytes large. +/// src_offset_bits Offset in bits from the source pointer. May exceed 8. +static inline void nunavutCopyBits(void* const dst, + const size_t dst_offset_bits, + const size_t length_bits, + const void* const src, + const size_t src_offset_bits) +{ + + + + if ((0U == (src_offset_bits % 8U)) && (0U == (dst_offset_bits % 8U))) // Aligned copy, optimized, most common case. + { + const size_t length_bytes = (size_t)(length_bits / 8U); + // Intentional violation of MISRA: Pointer arithmetics. This is done to remove the API constraint that + // offsets be under 8 bits. Fewer constraints reduce the chance of API misuse. + const uint8_t* const psrc = (src_offset_bits / 8U) + (const uint8_t*) src; // NOSONAR NOLINT + uint8_t* const pdst = (dst_offset_bits / 8U) + (uint8_t*) dst; // NOSONAR NOLINT + (void) memmove(pdst, psrc, length_bytes); + const uint8_t length_mod = (uint8_t)(length_bits % 8U); + if (0U != length_mod) // If the length is unaligned, the last byte requires special treatment. + { + // Intentional violation of MISRA: Pointer arithmetics. It is unavoidable in this context. + const uint8_t* const last_src = psrc + length_bytes; // NOLINT NOSONAR + uint8_t* const last_dst = pdst + length_bytes; // NOLINT NOSONAR + + const uint8_t mask = (uint8_t)((1U << length_mod) - 1U); + *last_dst = (*last_dst & (uint8_t)~mask) | (*last_src & mask); + } + } + else + { + // The algorithm was originally designed by Ben Dyer for Libuavcan v0: + // https://github.com/OpenCyphal/libuavcan/blob/legacy-v0/libuavcan/src/marshal/uc_bit_array_copy.cpp + // This version is modified for v1 where the bit order is the opposite. + const uint8_t* const psrc = (const uint8_t*) src; + uint8_t* const pdst = (uint8_t*) dst; + size_t src_off = src_offset_bits; + size_t dst_off = dst_offset_bits; + const size_t last_bit = src_off + length_bits; + + + while (last_bit > src_off) + { + const uint8_t src_mod = (uint8_t)(src_off % 8U); + const uint8_t dst_mod = (uint8_t)(dst_off % 8U); + const uint8_t max_mod = (src_mod > dst_mod) ? src_mod : dst_mod; + const uint8_t size = (uint8_t) nunavutChooseMin(8U - max_mod, last_bit - src_off); + + + // Suppress a false warning from Clang-Tidy & Sonar that size is being over-shifted. It's not. + const uint8_t mask = (uint8_t)((((1U << size) - 1U) << dst_mod) & 0xFFU); // NOLINT NOSONAR + + // Intentional violation of MISRA: indexing on a pointer. + // This simplifies the implementation greatly and avoids pointer arithmetics. + const uint8_t in = (uint8_t)((uint8_t)(psrc[src_off / 8U] >> src_mod) << dst_mod) & 0xFFU; // NOSONAR + // Intentional violation of MISRA: indexing on a pointer. + // This simplifies the implementation greatly and avoids pointer arithmetics. + const uint8_t a = pdst[dst_off / 8U] & ((uint8_t) ~mask); // NOSONAR + const uint8_t b = in & mask; + // Intentional violation of MISRA: indexing on a pointer. + // This simplifies the implementation greatly and avoids pointer arithmetics. + pdst[dst_off / 8U] = a | b; // NOSONAR + src_off += size; + dst_off += size; + } + + } +} + +/// This function is intended for deserialization of contiguous sequences of zero-cost primitives. +/// It extracts (len_bits) bits that are offset by (off_bits) from the origin of (buf) whose size is (buf_size_bytes). +/// If the requested (len_bits+off_bits) overruns the buffer, the missing bits are implicitly zero-extended. +/// If (len_bits % 8 != 0), the output buffer is right-zero-padded up to the next byte boundary. +/// If (off_bits % 8 == 0), the operation is delegated to memmove(); otherwise, a much slower unaligned bit copy +/// algorithm is employed. See @ref nunavutCopyBits() for further details. +static inline void nunavutGetBits(void* const output, + const void* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const size_t len_bits) +{ + + + const size_t sat_bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, len_bits); + // Apply implicit zero extension. Normally, this is a no-op unless (len_bits > sat_bits) or (len_bits % 8 != 0). + // The former case ensures that if we're copying <8 bits, the MSB in the destination will be zeroed out. + (void) memset(((uint8_t*)output) + (sat_bits / 8U), 0, ((len_bits + 7U) / 8U) - (sat_bits / 8U)); + nunavutCopyBits(output, 0U, sat_bits, buf, off_bits); +} + +// ---------------------------------------------------- INTEGER ---------------------------------------------------- + +/// Serialize a DSDL field value at the specified bit offset from the beginning of the destination buffer. +/// The behavior is undefined if the input pointer is NULL. The time complexity is linear of the bit length. +/// One-bit-wide signed integers are processed without raising an error but the result is unspecified. +/// +/// Arguments: +/// buf Destination buffer where the result will be stored. +/// buf_size_bytes Size of the above, in bytes. +/// off_bits Offset, in bits, from the beginning of the buffer. May exceed one byte. +/// value The value itself (in case of integers it is promoted to 64-bit for unification). +/// len_bits Length of the serialized representation, in bits. Zero has no effect. Values >64 bit saturated. + +static inline int8_t nunavutSetBit( + uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const bool value) +{ + + if ((buf_size_bytes * 8) <= off_bits) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + const uint8_t val = value ? 1U : 0U; + nunavutCopyBits(buf, off_bits, 1U, &val, 0U); + return NUNAVUT_SUCCESS; +} + +static inline int8_t nunavutSetUxx( + uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint64_t value, + const uint8_t len_bits) +{ + static_assert(64U == (sizeof(uint64_t) * 8U), "Unexpected size of uint64_t"); + + if ((buf_size_bytes * 8) < (off_bits + len_bits)) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + const size_t saturated_len_bits = nunavutChooseMin(len_bits, 64U); + const uint8_t tmp[sizeof(uint64_t)] = { + (uint8_t)((value >> 0U) & 0xFFU), + (uint8_t)((value >> 8U) & 0xFFU), + (uint8_t)((value >> 16U) & 0xFFU), + (uint8_t)((value >> 24U) & 0xFFU), + (uint8_t)((value >> 32U) & 0xFFU), + (uint8_t)((value >> 40U) & 0xFFU), + (uint8_t)((value >> 48U) & 0xFFU), + (uint8_t)((value >> 56U) & 0xFFU), + }; + nunavutCopyBits(buf, off_bits, saturated_len_bits, &tmp[0], 0U); + return NUNAVUT_SUCCESS; +} + +static inline int8_t nunavutSetIxx( + uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const int64_t value, + const uint8_t len_bits) +{ + // The naive sign conversion is safe and portable according to the C standard: + // 6.3.1.3.3: if the new type is unsigned, the value is converted by repeatedly adding or subtracting one more + // than the maximum value that can be represented in the new type until the value is in the range of the new type. + return nunavutSetUxx(buf, buf_size_bytes, off_bits, (uint64_t) value, len_bits); +} + +/// Deserialize a DSDL field value located at the specified bit offset from the beginning of the source buffer. +/// If the deserialized value extends beyond the end of the buffer, the missing bits are taken as zero, as required +/// by the DSDL specification (see Implicit Zero Extension Rule, IZER). +/// +/// If len_bits is greater than the return type, extra bits will be truncated per standard narrowing conversion rules. +/// If len_bits is shorter than the return type, missing bits will be zero per standard integer promotion rules. +/// Essentially, for integers, it would be enough to have 64-bit versions only; narrower variants exist only to avoid +/// narrowing type conversions of the result and for some performance gains. +/// +/// The behavior is undefined if the input pointer is NULL. The time complexity is linear of the bit length. +/// One-bit-wide signed integers are processed without raising an error but the result is unspecified. +/// +/// Arguments: +/// buf Source buffer where the serialized representation will be read from. +/// buf_size_bytes The size of the source buffer, in bytes. Reads past this limit will return zero bits. +/// off_bits Offset, in bits, from the beginning of the buffer. May exceed one byte. +/// len_bits Length of the serialized representation, in bits. Zero returns 0. Out-of-range values saturated. + +static inline uint8_t nunavutGetU8(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits); + +static inline bool nunavutGetBit(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits) +{ + return 1U == nunavutGetU8(buf, buf_size_bytes, off_bits, 1U); +} + +static inline uint8_t nunavutGetU8(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 8U)); + + uint8_t val = 0; + nunavutCopyBits(&val, 0U, bits, buf, off_bits); + return val; +} + +static inline uint16_t nunavutGetU16(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 16U)); + + uint8_t tmp[sizeof(uint16_t)] = {0}; + nunavutCopyBits(&tmp[0], 0U, bits, buf, off_bits); + return (uint16_t)(tmp[0] | (uint16_t)(((uint16_t) tmp[1]) << 8U)); +} + +static inline uint32_t nunavutGetU32(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 32U)); + + uint8_t tmp[sizeof(uint32_t)] = {0}; + nunavutCopyBits(&tmp[0], 0U, bits, buf, off_bits); + return (uint32_t)(tmp[0] | ((uint32_t) tmp[1] << 8U) | ((uint32_t) tmp[2] << 16U) | ((uint32_t) tmp[3] << 24U)); +} + +static inline uint64_t nunavutGetU64(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 64U)); + + uint8_t tmp[sizeof(uint64_t)] = {0}; + nunavutCopyBits(&tmp[0], 0U, bits, buf, off_bits); + return (uint64_t)(tmp[0] | + ((uint64_t) tmp[1] << 8U) | + ((uint64_t) tmp[2] << 16U) | + ((uint64_t) tmp[3] << 24U) | + ((uint64_t) tmp[4] << 32U) | + ((uint64_t) tmp[5] << 40U) | + ((uint64_t) tmp[6] << 48U) | + ((uint64_t) tmp[7] << 56U)); +} + +static inline int8_t nunavutGetI8(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + const uint8_t sat = (uint8_t) nunavutChooseMin(len_bits, 8U); + uint8_t val = nunavutGetU8(buf, buf_size_bytes, off_bits, sat); + const bool neg = (sat > 0U) && ((val & (1ULL << (sat - 1U))) != 0U); + val = ((sat < 8U) && neg) ? (uint8_t)(val | ~((1U << sat) - 1U)) : val; // Sign extension + return neg ? (int8_t)((-(int8_t)(uint8_t) ~val) - 1) : (int8_t) val; +} + +static inline int16_t nunavutGetI16(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + const uint8_t sat = (uint8_t) nunavutChooseMin(len_bits, 16U); + uint16_t val = nunavutGetU16(buf, buf_size_bytes, off_bits, sat); + const bool neg = (sat > 0U) && ((val & (1ULL << (sat - 1U))) != 0U); + val = ((sat < 16U) && neg) ? (uint16_t)(val | ~((1U << sat) - 1U)) : val; // Sign extension + return neg ? (int16_t)((-(int16_t)(uint16_t) ~val) - 1) : (int16_t) val; +} + +static inline int32_t nunavutGetI32(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + const uint8_t sat = (uint8_t) nunavutChooseMin(len_bits, 32U); + uint32_t val = nunavutGetU32(buf, buf_size_bytes, off_bits, sat); + const bool neg = (sat > 0U) && ((val & (1ULL << (sat - 1U))) != 0U); + val = ((sat < 32U) && neg) ? (uint32_t)(val | ~((1UL << sat) - 1U)) : val; // Sign extension + return neg ? (int32_t)((-(int32_t) ~val) - 1) : (int32_t) val; +} + +static inline int64_t nunavutGetI64(const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const uint8_t len_bits) +{ + const uint8_t sat = (uint8_t) nunavutChooseMin(len_bits, 64U); + uint64_t val = nunavutGetU64(buf, buf_size_bytes, off_bits, sat); + const bool neg = (sat > 0U) && ((val & (1ULL << (sat - 1U))) != 0U); + val = ((sat < 64U) && neg) ? (uint64_t)(val | ~((1ULL << sat) - 1U)) : val; // Sign extension + return neg ? (int64_t)((-(int64_t) ~val) - 1) : (int64_t) val; +} + +// ---------------------------------------------------- FLOAT16 ---------------------------------------------------- + +static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, + "The target platform does not support IEEE754 floating point operations."); +static_assert(32U == (sizeof(float) * 8U), "Unsupported floating point model"); + +/// Converts a single-precision float into the binary representation of the value as a half-precision IEEE754 value. +static inline uint16_t nunavutFloat16Pack(const float value) +{ + typedef union // NOSONAR + { + uint32_t bits; + float real; + } Float32Bits; + + // The no-lint statements suppress the warning about the use of union. This is required for low-level bit access. + const uint32_t round_mask = ~(uint32_t) 0x0FFFU; + Float32Bits f32inf; // NOSONAR + Float32Bits f16inf; // NOSONAR + Float32Bits magic; // NOSONAR + Float32Bits in; // NOSONAR + f32inf.bits = ((uint32_t) 255U) << 23U; + f16inf.bits = ((uint32_t) 31U) << 23U; + magic.bits = ((uint32_t) 15U) << 23U; + in.real = value; + const uint32_t sign = in.bits & (((uint32_t) 1U) << 31U); + in.bits ^= sign; + uint16_t out = 0; + if (in.bits >= f32inf.bits) + { + if ((in.bits & 0x7FFFFFUL) != 0) + { + out = 0x7E00U; + } + else + { + out = (in.bits > f32inf.bits) ? (uint16_t) 0x7FFFU : (uint16_t) 0x7C00U; + } + } + else + { + in.bits &= round_mask; + in.real *= magic.real; + in.bits -= round_mask; + if (in.bits > f16inf.bits) + { + in.bits = f16inf.bits; + } + out = (uint16_t)(in.bits >> 13U); + } + out |= (uint16_t)(sign >> 16U); + return out; +} + +static inline float nunavutFloat16Unpack(const uint16_t value) +{ + typedef union // NOSONAR + { + uint32_t bits; + float real; + } Float32Bits; + + // The no-lint statements suppress the warning about the use of union. This is required for low-level bit access. + Float32Bits magic; // NOSONAR + Float32Bits inf_nan; // NOSONAR + Float32Bits out; // NOSONAR + magic.bits = ((uint32_t) 0xEFU) << 23U; + inf_nan.bits = ((uint32_t) 0x8FU) << 23U; + out.bits = ((uint32_t)(value & 0x7FFFU)) << 13U; + out.real *= magic.real; + if (out.real >= inf_nan.real) + { + out.bits |= ((uint32_t) 0xFFU) << 23U; + } + out.bits |= ((uint32_t)(value & 0x8000U)) << 16U; + return out.real; +} + +static inline int8_t nunavutSetF16( + uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const float value) +{ + return nunavutSetUxx(buf, buf_size_bytes, off_bits, nunavutFloat16Pack(value), 16U); +} + +static inline float nunavutGetF16( + const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits) +{ + return nunavutFloat16Unpack(nunavutGetU16(buf, buf_size_bytes, off_bits, 16U)); +} + +// ---------------------------------------------------- FLOAT32 ---------------------------------------------------- + +static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, + "The target platform does not support IEEE754 floating point operations."); +static_assert(32U == (sizeof(float) * 8U), "Unsupported floating point model"); + +static inline int8_t nunavutSetF32( + uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const float value) +{ + // Intentional violation of MISRA: use union to perform fast conversion from an IEEE 754-compatible native + // representation into a serializable integer. The assumptions about the target platform properties are made + // clear. In the future we may add a more generic conversion that is platform-invariant. + union // NOSONAR + { + float fl; + uint32_t in; + } const tmp = {value}; // NOSONAR + return nunavutSetUxx(buf, buf_size_bytes, off_bits, tmp.in, sizeof(tmp) * 8U); +} + +static inline float nunavutGetF32( + const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits) +{ + // Intentional violation of MISRA: use union to perform fast conversion to an IEEE 754-compatible native + // representation into a serializable integer. The assumptions about the target platform properties are made + // clear. In the future we may add a more generic conversion that is platform-invariant. + union // NOSONAR + { + uint32_t in; + float fl; + } const tmp = {nunavutGetU32(buf, buf_size_bytes, off_bits, 32U)}; + return tmp.fl; +} + +// ---------------------------------------------------- FLOAT64 ---------------------------------------------------- + +static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, + "The target platform does not support IEEE754 double-precision floating point operations."); +static_assert(64U == (sizeof(double) * 8U), "Unsupported floating point model"); + +static inline int8_t nunavutSetF64( + uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits, + const double value) +{ + // Intentional violation of MISRA: use union to perform fast conversion from an IEEE 754-compatible native + // representation into a serializable integer. The assumptions about the target platform properties are made + // clear. In the future we may add a more generic conversion that is platform-invariant. + union // NOSONAR + { + double fl; + uint64_t in; + } const tmp = {value}; // NOSONAR + return nunavutSetUxx(buf, buf_size_bytes, off_bits, tmp.in, sizeof(tmp) * 8U); +} + +static inline double nunavutGetF64( + const uint8_t* const buf, + const size_t buf_size_bytes, + const size_t off_bits) +{ + // Intentional violation of MISRA: use union to perform fast conversion to an IEEE 754-compatible native + // representation into a serializable integer. The assumptions about the target platform properties are made + // clear. In the future we may add a more generic conversion that is platform-invariant. + union // NOSONAR + { + uint64_t in; + double fl; + } const tmp = {nunavutGetU64(buf, buf_size_bytes, off_bits, 64U)}; + return tmp.fl; +} + +#ifdef __cplusplus +} +#endif + +#endif // NUNAVUT_SUPPORT_SERIALIZATION_H_INCLUDED diff --git a/components/esp_nunavut/nunavut/uavcan/_register/Access_1_0.h b/components/esp_nunavut/nunavut/uavcan/_register/Access_1_0.h new file mode 100644 index 0000000..100f0b9 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/_register/Access_1_0.h @@ -0,0 +1,492 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/384.Access.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.104129 UTC +// Is deprecated: no +// Fixed port-ID: 384 +// Full name: uavcan.register.Access +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_REGISTER_ACCESS_1_0_INCLUDED_ +#define UAVCAN_REGISTER_ACCESS_1_0_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/384.Access.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/384.Access.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/384.Access.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/384.Access.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/384.Access.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_register_Access_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_register_Access_1_0_FIXED_PORT_ID_ 384U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.Access.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_Access_1_0_FULL_NAME_ "uavcan.register.Access" +#define uavcan_register_Access_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.Access.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.Access.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_Access_Request_1_0_FULL_NAME_ "uavcan.register.Access.Request" +#define uavcan_register_Access_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.Access.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_register_Access_Request_1_0_EXTENT_BYTES_ 515UL +#define uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 515UL +static_assert(uavcan_register_Access_Request_1_0_EXTENT_BYTES_ >= uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.register.Name.1.0 name + uavcan_register_Name_1_0 name; + + /// uavcan.register.Value.1.0 value + uavcan_register_Value_1_0 value; +} uavcan_register_Access_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Access_Request_1_0_serialize_( + const uavcan_register_Access_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 4120UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.register.Name.1.0 name + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_register_Name_1_0_serialize_( + &obj->name, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.register.Value.1.0 value + size_t _size_bytes1_ = 259UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_register_Value_1_0_serialize_( + &obj->value, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Access_Request_1_0_deserialize_( + uavcan_register_Access_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.register.Name.1.0 name + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_register_Name_1_0_deserialize_( + &out_obj->name, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.register.Value.1.0 value + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_register_Value_1_0_deserialize_( + &out_obj->value, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_register_Access_Request_1_0_initialize_(uavcan_register_Access_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_register_Access_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.Access.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_Access_Response_1_0_FULL_NAME_ "uavcan.register.Access.Response" +#define uavcan_register_Access_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.Access.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_register_Access_Response_1_0_EXTENT_BYTES_ 267UL +#define uavcan_register_Access_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 267UL +static_assert(uavcan_register_Access_Response_1_0_EXTENT_BYTES_ >= uavcan_register_Access_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated bool mutable + bool _mutable; + + /// saturated bool persistent + bool persistent; + + /// uavcan.register.Value.1.0 value + uavcan_register_Value_1_0 value; +} uavcan_register_Access_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_register_Access_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Access_Response_1_0_serialize_( + const uavcan_register_Access_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2136UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes4_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err6_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err6_ < 0) + { + return _err6_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + } + { // saturated bool mutable + buffer[offset_bits / 8U] = obj->_mutable ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool persistent + if (obj->persistent) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void6 + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 6U); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += 6UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _pad2_; + } + { // uavcan.register.Value.1.0 value + size_t _size_bytes5_ = 259UL; // Nested object (max) size, in bytes. + int8_t _err9_ = uavcan_register_Value_1_0_serialize_( + &obj->value, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err9_ < 0) + { + return _err9_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err10_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Access_Response_1_0_deserialize_( + uavcan_register_Access_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err11_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes6_); + if (_err11_ < 0) + { + return _err11_; + } + offset_bits += _size_bytes6_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated bool mutable + if (offset_bits < capacity_bits) + { + out_obj->_mutable = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->_mutable = false; + } + offset_bits += 1U; + // saturated bool persistent + if (offset_bits < capacity_bits) + { + out_obj->persistent = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->persistent = false; + } + offset_bits += 1U; + // void6 + offset_bits += 6; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.register.Value.1.0 value + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err12_ = uavcan_register_Value_1_0_deserialize_( + &out_obj->value, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err12_ < 0) + { + return _err12_; + } + offset_bits += _size_bytes7_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_register_Access_Response_1_0_initialize_(uavcan_register_Access_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_register_Access_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_ACCESS_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/_register/List_1_0.h b/components/esp_nunavut/nunavut/uavcan/_register/List_1_0.h new file mode 100644 index 0000000..2dab748 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/_register/List_1_0.h @@ -0,0 +1,357 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/385.List.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.118011 UTC +// Is deprecated: no +// Fixed port-ID: 385 +// Full name: uavcan.register.List +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_REGISTER_LIST_1_0_INCLUDED_ +#define UAVCAN_REGISTER_LIST_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/385.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/385.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/385.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/385.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/385.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_register_List_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_register_List_1_0_FIXED_PORT_ID_ 385U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.List.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_List_1_0_FULL_NAME_ "uavcan.register.List" +#define uavcan_register_List_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.List.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.List.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_List_Request_1_0_FULL_NAME_ "uavcan.register.List.Request" +#define uavcan_register_List_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.List.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_register_List_Request_1_0_EXTENT_BYTES_ 2UL +#define uavcan_register_List_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_register_List_Request_1_0_EXTENT_BYTES_ >= uavcan_register_List_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint16 index + uint16_t index; +} uavcan_register_List_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_register_List_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_List_Request_1_0_serialize_( + const uavcan_register_List_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 index + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->index, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_List_Request_1_0_deserialize_( + uavcan_register_List_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 index + out_obj->index = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_register_List_Request_1_0_initialize_(uavcan_register_List_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_register_List_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.List.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_List_Response_1_0_FULL_NAME_ "uavcan.register.List.Response" +#define uavcan_register_List_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.List.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_register_List_Response_1_0_EXTENT_BYTES_ 256UL +#define uavcan_register_List_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 256UL +static_assert(uavcan_register_List_Response_1_0_EXTENT_BYTES_ >= uavcan_register_List_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.register.Name.1.0 name + uavcan_register_Name_1_0 name; +} uavcan_register_List_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_register_List_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_List_Response_1_0_serialize_( + const uavcan_register_List_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2048UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.register.Name.1.0 name + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_register_Name_1_0_serialize_( + &obj->name, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_List_Response_1_0_deserialize_( + uavcan_register_List_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.register.Name.1.0 name + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_register_Name_1_0_deserialize_( + &out_obj->name, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_register_List_Response_1_0_initialize_(uavcan_register_List_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_register_List_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_LIST_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/_register/Name_1_0.h b/components/esp_nunavut/nunavut/uavcan/_register/Name_1_0.h new file mode 100644 index 0000000..c2520dd --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/_register/Name_1_0.h @@ -0,0 +1,242 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Name.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.126482 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.register.Name +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_REGISTER_NAME_1_0_INCLUDED_ +#define UAVCAN_REGISTER_NAME_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Name.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Name.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Name.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Name.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Name.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_register_Name_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.Name.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_Name_1_0_FULL_NAME_ "uavcan.register.Name" +#define uavcan_register_Name_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.Name.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_register_Name_1_0_EXTENT_BYTES_ 256UL +#define uavcan_register_Name_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 256UL +static_assert(uavcan_register_Name_1_0_EXTENT_BYTES_ >= uavcan_register_Name_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=255] name +#define uavcan_register_Name_1_0_name_ARRAY_CAPACITY_ 255U +#define uavcan_register_Name_1_0_name_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=255] name + struct /// Array address equivalence guarantee: &elements[0] == &name + { + uint8_t elements[uavcan_register_Name_1_0_name_ARRAY_CAPACITY_]; + size_t count; + } name; +} uavcan_register_Name_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_register_Name_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Name_1_0_serialize_( + const uavcan_register_Name_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2048UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=255] name + if (obj->name.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->name.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->name.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->name.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Name_1_0_deserialize_( + uavcan_register_Name_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=255] name + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->name.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->name.count = 0U; + } + offset_bits += 8U; + if (out_obj->name.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->name.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->name.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->name.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_register_Name_1_0_initialize_(uavcan_register_Name_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_register_Name_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_NAME_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/_register/Value_1_0.h b/components/esp_nunavut/nunavut/uavcan/_register/Value_1_0.h new file mode 100644 index 0000000..41756c8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/_register/Value_1_0.h @@ -0,0 +1,878 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Value.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.131457 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.register.Value +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_REGISTER_VALUE_1_0_INCLUDED_ +#define UAVCAN_REGISTER_VALUE_1_0_INCLUDED_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Value.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Value.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Value.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Value.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/register/Value.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_register_Value_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.register.Value.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_register_Value_1_0_FULL_NAME_ "uavcan.register.Value" +#define uavcan_register_Value_1_0_FULL_NAME_AND_VERSION_ "uavcan.register.Value.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_register_Value_1_0_EXTENT_BYTES_ 259UL +#define uavcan_register_Value_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 259UL +static_assert(uavcan_register_Value_1_0_EXTENT_BYTES_ >= uavcan_register_Value_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// uavcan.primitive.Empty.1.0 empty + uavcan_primitive_Empty_1_0 empty; + + /// uavcan.primitive.String.1.0 string + uavcan_primitive_String_1_0 _string; + + /// uavcan.primitive.Unstructured.1.0 unstructured + uavcan_primitive_Unstructured_1_0 unstructured; + + /// uavcan.primitive.array.Bit.1.0 bit + uavcan_primitive_array_Bit_1_0 bit; + + /// uavcan.primitive.array.Integer64.1.0 integer64 + uavcan_primitive_array_Integer64_1_0 integer64; + + /// uavcan.primitive.array.Integer32.1.0 integer32 + uavcan_primitive_array_Integer32_1_0 integer32; + + /// uavcan.primitive.array.Integer16.1.0 integer16 + uavcan_primitive_array_Integer16_1_0 integer16; + + /// uavcan.primitive.array.Integer8.1.0 integer8 + uavcan_primitive_array_Integer8_1_0 integer8; + + /// uavcan.primitive.array.Natural64.1.0 natural64 + uavcan_primitive_array_Natural64_1_0 natural64; + + /// uavcan.primitive.array.Natural32.1.0 natural32 + uavcan_primitive_array_Natural32_1_0 natural32; + + /// uavcan.primitive.array.Natural16.1.0 natural16 + uavcan_primitive_array_Natural16_1_0 natural16; + + /// uavcan.primitive.array.Natural8.1.0 natural8 + uavcan_primitive_array_Natural8_1_0 natural8; + + /// uavcan.primitive.array.Real64.1.0 real64 + uavcan_primitive_array_Real64_1_0 real64; + + /// uavcan.primitive.array.Real32.1.0 real32 + uavcan_primitive_array_Real32_1_0 real32; + + /// uavcan.primitive.array.Real16.1.0 real16 + uavcan_primitive_array_Real16_1_0 real16; + }; + uint8_t _tag_; +} uavcan_register_Value_1_0; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_register_Value_1_0_UNION_OPTION_COUNT_ 15U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_register_Value_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Value_1_0_serialize_( + const uavcan_register_Value_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2072UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // uavcan.primitive.Empty.1.0 empty + { + size_t _size_bytes0_ = 0UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_primitive_Empty_1_0_serialize_( + &obj->empty, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + else if (1U == obj->_tag_) // uavcan.primitive.String.1.0 string + { + size_t _size_bytes1_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_primitive_String_1_0_serialize_( + &obj->_string, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else if (2U == obj->_tag_) // uavcan.primitive.Unstructured.1.0 unstructured + { + size_t _size_bytes2_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_primitive_Unstructured_1_0_serialize_( + &obj->unstructured, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + else if (3U == obj->_tag_) // uavcan.primitive.array.Bit.1.0 bit + { + size_t _size_bytes3_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err3_ = uavcan_primitive_array_Bit_1_0_serialize_( + &obj->bit, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err3_ < 0) + { + return _err3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + } + else if (4U == obj->_tag_) // uavcan.primitive.array.Integer64.1.0 integer64 + { + size_t _size_bytes4_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_primitive_array_Integer64_1_0_serialize_( + &obj->integer64, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + } + else if (5U == obj->_tag_) // uavcan.primitive.array.Integer32.1.0 integer32 + { + size_t _size_bytes5_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err5_ = uavcan_primitive_array_Integer32_1_0_serialize_( + &obj->integer32, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err5_ < 0) + { + return _err5_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested object. + } + else if (6U == obj->_tag_) // uavcan.primitive.array.Integer16.1.0 integer16 + { + size_t _size_bytes6_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err6_ = uavcan_primitive_array_Integer16_1_0_serialize_( + &obj->integer16, &buffer[offset_bits / 8U], &_size_bytes6_); + if (_err6_ < 0) + { + return _err6_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes6_ * 8U; // Advance by the size of the nested object. + } + else if (7U == obj->_tag_) // uavcan.primitive.array.Integer8.1.0 integer8 + { + size_t _size_bytes7_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err7_ = uavcan_primitive_array_Integer8_1_0_serialize_( + &obj->integer8, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err7_ < 0) + { + return _err7_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes7_ * 8U; // Advance by the size of the nested object. + } + else if (8U == obj->_tag_) // uavcan.primitive.array.Natural64.1.0 natural64 + { + size_t _size_bytes8_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err8_ = uavcan_primitive_array_Natural64_1_0_serialize_( + &obj->natural64, &buffer[offset_bits / 8U], &_size_bytes8_); + if (_err8_ < 0) + { + return _err8_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes8_ * 8U; // Advance by the size of the nested object. + } + else if (9U == obj->_tag_) // uavcan.primitive.array.Natural32.1.0 natural32 + { + size_t _size_bytes9_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err9_ = uavcan_primitive_array_Natural32_1_0_serialize_( + &obj->natural32, &buffer[offset_bits / 8U], &_size_bytes9_); + if (_err9_ < 0) + { + return _err9_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes9_ * 8U; // Advance by the size of the nested object. + } + else if (10U == obj->_tag_) // uavcan.primitive.array.Natural16.1.0 natural16 + { + size_t _size_bytes10_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err10_ = uavcan_primitive_array_Natural16_1_0_serialize_( + &obj->natural16, &buffer[offset_bits / 8U], &_size_bytes10_); + if (_err10_ < 0) + { + return _err10_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes10_ * 8U; // Advance by the size of the nested object. + } + else if (11U == obj->_tag_) // uavcan.primitive.array.Natural8.1.0 natural8 + { + size_t _size_bytes11_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err11_ = uavcan_primitive_array_Natural8_1_0_serialize_( + &obj->natural8, &buffer[offset_bits / 8U], &_size_bytes11_); + if (_err11_ < 0) + { + return _err11_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes11_ * 8U; // Advance by the size of the nested object. + } + else if (12U == obj->_tag_) // uavcan.primitive.array.Real64.1.0 real64 + { + size_t _size_bytes12_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err12_ = uavcan_primitive_array_Real64_1_0_serialize_( + &obj->real64, &buffer[offset_bits / 8U], &_size_bytes12_); + if (_err12_ < 0) + { + return _err12_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes12_ * 8U; // Advance by the size of the nested object. + } + else if (13U == obj->_tag_) // uavcan.primitive.array.Real32.1.0 real32 + { + size_t _size_bytes13_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err13_ = uavcan_primitive_array_Real32_1_0_serialize_( + &obj->real32, &buffer[offset_bits / 8U], &_size_bytes13_); + if (_err13_ < 0) + { + return _err13_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes13_ * 8U; // Advance by the size of the nested object. + } + else if (14U == obj->_tag_) // uavcan.primitive.array.Real16.1.0 real16 + { + size_t _size_bytes14_ = 257UL; // Nested object (max) size, in bytes. + int8_t _err14_ = uavcan_primitive_array_Real16_1_0_serialize_( + &obj->real16, &buffer[offset_bits / 8U], &_size_bytes14_); + if (_err14_ < 0) + { + return _err14_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes14_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err15_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err15_ < 0) + { + return _err15_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_register_Value_1_0_deserialize_( + uavcan_register_Value_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // uavcan.primitive.Empty.1.0 empty + { + { + size_t _size_bytes15_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err16_ = uavcan_primitive_Empty_1_0_deserialize_( + &out_obj->empty, &buffer[offset_bits / 8U], &_size_bytes15_); + if (_err16_ < 0) + { + return _err16_; + } + offset_bits += _size_bytes15_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (1U == out_obj->_tag_) // uavcan.primitive.String.1.0 string + { + { + size_t _size_bytes16_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err17_ = uavcan_primitive_String_1_0_deserialize_( + &out_obj->_string, &buffer[offset_bits / 8U], &_size_bytes16_); + if (_err17_ < 0) + { + return _err17_; + } + offset_bits += _size_bytes16_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (2U == out_obj->_tag_) // uavcan.primitive.Unstructured.1.0 unstructured + { + { + size_t _size_bytes17_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err18_ = uavcan_primitive_Unstructured_1_0_deserialize_( + &out_obj->unstructured, &buffer[offset_bits / 8U], &_size_bytes17_); + if (_err18_ < 0) + { + return _err18_; + } + offset_bits += _size_bytes17_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (3U == out_obj->_tag_) // uavcan.primitive.array.Bit.1.0 bit + { + { + size_t _size_bytes18_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err19_ = uavcan_primitive_array_Bit_1_0_deserialize_( + &out_obj->bit, &buffer[offset_bits / 8U], &_size_bytes18_); + if (_err19_ < 0) + { + return _err19_; + } + offset_bits += _size_bytes18_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (4U == out_obj->_tag_) // uavcan.primitive.array.Integer64.1.0 integer64 + { + { + size_t _size_bytes19_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err20_ = uavcan_primitive_array_Integer64_1_0_deserialize_( + &out_obj->integer64, &buffer[offset_bits / 8U], &_size_bytes19_); + if (_err20_ < 0) + { + return _err20_; + } + offset_bits += _size_bytes19_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (5U == out_obj->_tag_) // uavcan.primitive.array.Integer32.1.0 integer32 + { + { + size_t _size_bytes20_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err21_ = uavcan_primitive_array_Integer32_1_0_deserialize_( + &out_obj->integer32, &buffer[offset_bits / 8U], &_size_bytes20_); + if (_err21_ < 0) + { + return _err21_; + } + offset_bits += _size_bytes20_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (6U == out_obj->_tag_) // uavcan.primitive.array.Integer16.1.0 integer16 + { + { + size_t _size_bytes21_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err22_ = uavcan_primitive_array_Integer16_1_0_deserialize_( + &out_obj->integer16, &buffer[offset_bits / 8U], &_size_bytes21_); + if (_err22_ < 0) + { + return _err22_; + } + offset_bits += _size_bytes21_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (7U == out_obj->_tag_) // uavcan.primitive.array.Integer8.1.0 integer8 + { + { + size_t _size_bytes22_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err23_ = uavcan_primitive_array_Integer8_1_0_deserialize_( + &out_obj->integer8, &buffer[offset_bits / 8U], &_size_bytes22_); + if (_err23_ < 0) + { + return _err23_; + } + offset_bits += _size_bytes22_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (8U == out_obj->_tag_) // uavcan.primitive.array.Natural64.1.0 natural64 + { + { + size_t _size_bytes23_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err24_ = uavcan_primitive_array_Natural64_1_0_deserialize_( + &out_obj->natural64, &buffer[offset_bits / 8U], &_size_bytes23_); + if (_err24_ < 0) + { + return _err24_; + } + offset_bits += _size_bytes23_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (9U == out_obj->_tag_) // uavcan.primitive.array.Natural32.1.0 natural32 + { + { + size_t _size_bytes24_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err25_ = uavcan_primitive_array_Natural32_1_0_deserialize_( + &out_obj->natural32, &buffer[offset_bits / 8U], &_size_bytes24_); + if (_err25_ < 0) + { + return _err25_; + } + offset_bits += _size_bytes24_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (10U == out_obj->_tag_) // uavcan.primitive.array.Natural16.1.0 natural16 + { + { + size_t _size_bytes25_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err26_ = uavcan_primitive_array_Natural16_1_0_deserialize_( + &out_obj->natural16, &buffer[offset_bits / 8U], &_size_bytes25_); + if (_err26_ < 0) + { + return _err26_; + } + offset_bits += _size_bytes25_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (11U == out_obj->_tag_) // uavcan.primitive.array.Natural8.1.0 natural8 + { + { + size_t _size_bytes26_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err27_ = uavcan_primitive_array_Natural8_1_0_deserialize_( + &out_obj->natural8, &buffer[offset_bits / 8U], &_size_bytes26_); + if (_err27_ < 0) + { + return _err27_; + } + offset_bits += _size_bytes26_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (12U == out_obj->_tag_) // uavcan.primitive.array.Real64.1.0 real64 + { + { + size_t _size_bytes27_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err28_ = uavcan_primitive_array_Real64_1_0_deserialize_( + &out_obj->real64, &buffer[offset_bits / 8U], &_size_bytes27_); + if (_err28_ < 0) + { + return _err28_; + } + offset_bits += _size_bytes27_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (13U == out_obj->_tag_) // uavcan.primitive.array.Real32.1.0 real32 + { + { + size_t _size_bytes28_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err29_ = uavcan_primitive_array_Real32_1_0_deserialize_( + &out_obj->real32, &buffer[offset_bits / 8U], &_size_bytes28_); + if (_err29_ < 0) + { + return _err29_; + } + offset_bits += _size_bytes28_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (14U == out_obj->_tag_) // uavcan.primitive.array.Real16.1.0 real16 + { + { + size_t _size_bytes29_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err30_ = uavcan_primitive_array_Real16_1_0_deserialize_( + &out_obj->real16, &buffer[offset_bits / 8U], &_size_bytes29_); + if (_err30_ < 0) + { + return _err30_; + } + offset_bits += _size_bytes29_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_register_Value_1_0_initialize_(uavcan_register_Value_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_register_Value_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "empty" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_empty_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "empty" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_empty_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "string" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_string_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "string" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_string_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +/// Mark option "unstructured" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_unstructured_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 2; + } +} + +/// Check if option "unstructured" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_unstructured_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 2)); +} + +/// Mark option "bit" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_bit_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 3; + } +} + +/// Check if option "bit" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_bit_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 3)); +} + +/// Mark option "integer64" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_integer64_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 4; + } +} + +/// Check if option "integer64" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_integer64_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 4)); +} + +/// Mark option "integer32" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_integer32_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 5; + } +} + +/// Check if option "integer32" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_integer32_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 5)); +} + +/// Mark option "integer16" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_integer16_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 6; + } +} + +/// Check if option "integer16" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_integer16_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 6)); +} + +/// Mark option "integer8" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_integer8_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 7; + } +} + +/// Check if option "integer8" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_integer8_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 7)); +} + +/// Mark option "natural64" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_natural64_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 8; + } +} + +/// Check if option "natural64" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_natural64_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 8)); +} + +/// Mark option "natural32" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_natural32_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 9; + } +} + +/// Check if option "natural32" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_natural32_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 9)); +} + +/// Mark option "natural16" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_natural16_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 10; + } +} + +/// Check if option "natural16" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_natural16_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 10)); +} + +/// Mark option "natural8" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_natural8_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 11; + } +} + +/// Check if option "natural8" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_natural8_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 11)); +} + +/// Mark option "real64" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_real64_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 12; + } +} + +/// Check if option "real64" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_real64_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 12)); +} + +/// Mark option "real32" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_real32_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 13; + } +} + +/// Check if option "real32" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_real32_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 13)); +} + +/// Mark option "real16" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_register_Value_1_0_select_real16_(uavcan_register_Value_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 14; + } +} + +/// Check if option "real16" is active. Returns false if @param obj is NULL. +static inline bool uavcan_register_Value_1_0_is_real16_(const uavcan_register_Value_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 14)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_VALUE_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_0.h b/components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_0.h new file mode 100644 index 0000000..404e4fb --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_0.h @@ -0,0 +1,315 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.226610 UTC +// Is deprecated: yes +// Fixed port-ID: 8184 +// Full name: uavcan.diagnostic.Record +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_DIAGNOSTIC_RECORD_1_0_INCLUDED_ +#define UAVCAN_DIAGNOSTIC_RECORD_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_diagnostic_Record_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_diagnostic_Record_1_0_FIXED_PORT_ID_ 8184U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.diagnostic.Record.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_diagnostic_Record_1_0_FULL_NAME_ "uavcan.diagnostic.Record" +#define uavcan_diagnostic_Record_1_0_FULL_NAME_AND_VERSION_ "uavcan.diagnostic.Record.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_diagnostic_Record_1_0_EXTENT_BYTES_ 300UL +#define uavcan_diagnostic_Record_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 121UL +static_assert(uavcan_diagnostic_Record_1_0_EXTENT_BYTES_ >= uavcan_diagnostic_Record_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=112] text +#define uavcan_diagnostic_Record_1_0_text_ARRAY_CAPACITY_ 112U +#define uavcan_diagnostic_Record_1_0_text_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// uavcan.diagnostic.Severity.1.0 severity + uavcan_diagnostic_Severity_1_0 severity; + + /// saturated uint8[<=112] text + struct /// Array address equivalence guarantee: &elements[0] == &text + { + uint8_t elements[uavcan_diagnostic_Record_1_0_text_ARRAY_CAPACITY_]; + size_t count; + } text; +} uavcan_diagnostic_Record_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_diagnostic_Record_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_diagnostic_Record_1_0_serialize_( + const uavcan_diagnostic_Record_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 968UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.diagnostic.Severity.1.0 severity + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_diagnostic_Severity_1_0_serialize_( + &obj->severity, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=112] text + if (obj->text.count > 112) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->text.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->text.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->text.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_diagnostic_Record_1_0_deserialize_( + uavcan_diagnostic_Record_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.diagnostic.Severity.1.0 severity + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_diagnostic_Severity_1_0_deserialize_( + &out_obj->severity, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=112] text + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->text.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->text.count = 0U; + } + offset_bits += 8U; + if (out_obj->text.count > 112U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->text.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->text.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->text.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_diagnostic_Record_1_0_initialize_(uavcan_diagnostic_Record_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_diagnostic_Record_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_DIAGNOSTIC_RECORD_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_1.h b/components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_1.h new file mode 100644 index 0000000..8a8cf5e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/diagnostic/Record_1_1.h @@ -0,0 +1,306 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.1.dsdl +// Generated at: 2024-09-11 21:29:52.971461 UTC +// Is deprecated: no +// Fixed port-ID: 8184 +// Full name: uavcan.diagnostic.Record +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_DIAGNOSTIC_RECORD_1_1_INCLUDED_ +#define UAVCAN_DIAGNOSTIC_RECORD_1_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/8184.Record.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_diagnostic_Record_1_1_HAS_FIXED_PORT_ID_ true +#define uavcan_diagnostic_Record_1_1_FIXED_PORT_ID_ 8184U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.diagnostic.Record.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_diagnostic_Record_1_1_FULL_NAME_ "uavcan.diagnostic.Record" +#define uavcan_diagnostic_Record_1_1_FULL_NAME_AND_VERSION_ "uavcan.diagnostic.Record.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_diagnostic_Record_1_1_EXTENT_BYTES_ 300UL +#define uavcan_diagnostic_Record_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 264UL +static_assert(uavcan_diagnostic_Record_1_1_EXTENT_BYTES_ >= uavcan_diagnostic_Record_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=255] text +#define uavcan_diagnostic_Record_1_1_text_ARRAY_CAPACITY_ 255U +#define uavcan_diagnostic_Record_1_1_text_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// uavcan.diagnostic.Severity.1.0 severity + uavcan_diagnostic_Severity_1_0 severity; + + /// saturated uint8[<=255] text + struct /// Array address equivalence guarantee: &elements[0] == &text + { + uint8_t elements[uavcan_diagnostic_Record_1_1_text_ARRAY_CAPACITY_]; + size_t count; + } text; +} uavcan_diagnostic_Record_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_diagnostic_Record_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_diagnostic_Record_1_1_serialize_( + const uavcan_diagnostic_Record_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2112UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.diagnostic.Severity.1.0 severity + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_diagnostic_Severity_1_0_serialize_( + &obj->severity, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=255] text + if (obj->text.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->text.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->text.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->text.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_diagnostic_Record_1_1_deserialize_( + uavcan_diagnostic_Record_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.diagnostic.Severity.1.0 severity + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_diagnostic_Severity_1_0_deserialize_( + &out_obj->severity, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=255] text + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->text.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->text.count = 0U; + } + offset_bits += 8U; + if (out_obj->text.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->text.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->text.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->text.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_diagnostic_Record_1_1_initialize_(uavcan_diagnostic_Record_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_diagnostic_Record_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_DIAGNOSTIC_RECORD_1_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/diagnostic/Severity_1_0.h b/components/esp_nunavut/nunavut/uavcan/diagnostic/Severity_1_0.h new file mode 100644 index 0000000..018a8b5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/diagnostic/Severity_1_0.h @@ -0,0 +1,235 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/Severity.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.232418 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.diagnostic.Severity +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_DIAGNOSTIC_SEVERITY_1_0_INCLUDED_ +#define UAVCAN_DIAGNOSTIC_SEVERITY_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/Severity.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/Severity.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/Severity.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/Severity.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/diagnostic/Severity.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_diagnostic_Severity_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.diagnostic.Severity.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_diagnostic_Severity_1_0_FULL_NAME_ "uavcan.diagnostic.Severity" +#define uavcan_diagnostic_Severity_1_0_FULL_NAME_AND_VERSION_ "uavcan.diagnostic.Severity.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_diagnostic_Severity_1_0_EXTENT_BYTES_ 1UL +#define uavcan_diagnostic_Severity_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_diagnostic_Severity_1_0_EXTENT_BYTES_ >= uavcan_diagnostic_Severity_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint3 TRACE = 0 +#define uavcan_diagnostic_Severity_1_0_TRACE (0U) + +/// saturated uint3 DEBUG = 1 +#define uavcan_diagnostic_Severity_1_0_DEBUG (1U) + +/// saturated uint3 INFO = 2 +#define uavcan_diagnostic_Severity_1_0_INFO (2U) + +/// saturated uint3 NOTICE = 3 +#define uavcan_diagnostic_Severity_1_0_NOTICE (3U) + +/// saturated uint3 WARNING = 4 +#define uavcan_diagnostic_Severity_1_0_WARNING (4U) + +/// saturated uint3 ERROR = 5 +#define uavcan_diagnostic_Severity_1_0_ERROR (5U) + +/// saturated uint3 CRITICAL = 6 +#define uavcan_diagnostic_Severity_1_0_CRITICAL (6U) + +/// saturated uint3 ALERT = 7 +#define uavcan_diagnostic_Severity_1_0_ALERT (7U) + +typedef struct +{ + /// saturated uint3 value + uint8_t value; +} uavcan_diagnostic_Severity_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_diagnostic_Severity_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_diagnostic_Severity_1_0_serialize_( + const uavcan_diagnostic_Severity_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint3 value + uint8_t _sat0_ = obj->value; + if (_sat0_ > 7U) + { + _sat0_ = 7U; + } + buffer[offset_bits / 8U] = (uint8_t)(_sat0_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 3U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_diagnostic_Severity_1_0_deserialize_( + uavcan_diagnostic_Severity_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint3 value + if ((offset_bits + 3U) <= capacity_bits) + { + out_obj->value = buffer[offset_bits / 8U] & 7U; + } + else + { + out_obj->value = 0U; + } + offset_bits += 3U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_diagnostic_Severity_1_0_initialize_(uavcan_diagnostic_Severity_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_diagnostic_Severity_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_DIAGNOSTIC_SEVERITY_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Error_1_0.h b/components/esp_nunavut/nunavut/uavcan/file/Error_1_0.h new file mode 100644 index 0000000..a4243c8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Error_1_0.h @@ -0,0 +1,234 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Error.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.236326 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.file.Error +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_ERROR_1_0_INCLUDED_ +#define UAVCAN_FILE_ERROR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Error.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Error.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Error.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Error.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Error.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_file_Error_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Error.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Error_1_0_FULL_NAME_ "uavcan.file.Error" +#define uavcan_file_Error_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Error.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Error_1_0_EXTENT_BYTES_ 2UL +#define uavcan_file_Error_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_file_Error_1_0_EXTENT_BYTES_ >= uavcan_file_Error_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 OK = 0 +#define uavcan_file_Error_1_0_OK (0U) + +/// saturated uint16 UNKNOWN_ERROR = 65535 +#define uavcan_file_Error_1_0_UNKNOWN_ERROR (65535U) + +/// saturated uint16 NOT_FOUND = 2 +#define uavcan_file_Error_1_0_NOT_FOUND (2U) + +/// saturated uint16 IO_ERROR = 5 +#define uavcan_file_Error_1_0_IO_ERROR (5U) + +/// saturated uint16 ACCESS_DENIED = 13 +#define uavcan_file_Error_1_0_ACCESS_DENIED (13U) + +/// saturated uint16 IS_DIRECTORY = 21 +#define uavcan_file_Error_1_0_IS_DIRECTORY (21U) + +/// saturated uint16 INVALID_VALUE = 22 +#define uavcan_file_Error_1_0_INVALID_VALUE (22U) + +/// saturated uint16 FILE_TOO_LARGE = 27 +#define uavcan_file_Error_1_0_FILE_TOO_LARGE (27U) + +/// saturated uint16 OUT_OF_SPACE = 28 +#define uavcan_file_Error_1_0_OUT_OF_SPACE (28U) + +/// saturated uint16 NOT_SUPPORTED = 38 +#define uavcan_file_Error_1_0_NOT_SUPPORTED (38U) + +typedef struct +{ + /// saturated uint16 value + uint16_t value; +} uavcan_file_Error_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Error_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Error_1_0_serialize_( + const uavcan_file_Error_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Error_1_0_deserialize_( + uavcan_file_Error_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Error_1_0_initialize_(uavcan_file_Error_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Error_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_ERROR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_1.h b/components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_1.h new file mode 100644 index 0000000..d1f4444 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_1.h @@ -0,0 +1,505 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.252317 UTC +// Is deprecated: yes +// Fixed port-ID: 405 +// Full name: uavcan.file.GetInfo +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_FILE_GET_INFO_0_1_INCLUDED_ +#define UAVCAN_FILE_GET_INFO_0_1_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_GetInfo_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_file_GetInfo_0_1_FIXED_PORT_ID_ 405U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.GetInfo.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_GetInfo_0_1_FULL_NAME_ "uavcan.file.GetInfo" +#define uavcan_file_GetInfo_0_1_FULL_NAME_AND_VERSION_ "uavcan.file.GetInfo.0.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.GetInfo.Request.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_GetInfo_Request_0_1_FULL_NAME_ "uavcan.file.GetInfo.Request" +#define uavcan_file_GetInfo_Request_0_1_FULL_NAME_AND_VERSION_ "uavcan.file.GetInfo.Request.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_GetInfo_Request_0_1_EXTENT_BYTES_ 300UL +#define uavcan_file_GetInfo_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 113UL +static_assert(uavcan_file_GetInfo_Request_0_1_EXTENT_BYTES_ >= uavcan_file_GetInfo_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Path.1.0 path + uavcan_file_Path_1_0 path; +} uavcan_file_GetInfo_Request_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_GetInfo_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Request_0_1_serialize_( + const uavcan_file_GetInfo_Request_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 904UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Path.1.0 path + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_file_Path_1_0_serialize_( + &obj->path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Request_0_1_deserialize_( + uavcan_file_GetInfo_Request_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Path.1.0 path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err2_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_GetInfo_Request_0_1_initialize_(uavcan_file_GetInfo_Request_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_GetInfo_Request_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.GetInfo.Response.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_GetInfo_Response_0_1_FULL_NAME_ "uavcan.file.GetInfo.Response" +#define uavcan_file_GetInfo_Response_0_1_FULL_NAME_AND_VERSION_ "uavcan.file.GetInfo.Response.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_GetInfo_Response_0_1_EXTENT_BYTES_ 48UL +#define uavcan_file_GetInfo_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 13UL +static_assert(uavcan_file_GetInfo_Response_0_1_EXTENT_BYTES_ >= uavcan_file_GetInfo_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; + + /// truncated uint40 size + uint64_t size; + + /// truncated uint40 unix_timestamp_of_last_modification + uint64_t unix_timestamp_of_last_modification; + + /// saturated bool is_file_not_directory + bool is_file_not_directory; + + /// saturated bool is_link + bool is_link; + + /// saturated bool is_readable + bool is_readable; + + /// saturated bool is_writeable + bool is_writeable; +} uavcan_file_GetInfo_Response_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_GetInfo_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Response_0_1_serialize_( + const uavcan_file_GetInfo_Response_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 104UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err3_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err3_ < 0) + { + return _err3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + { // truncated uint40 size + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->size, 40U); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += 40U; + } + { // truncated uint40 unix_timestamp_of_last_modification + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->unix_timestamp_of_last_modification, 40U); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 40U; + } + { // saturated bool is_file_not_directory + buffer[offset_bits / 8U] = obj->is_file_not_directory ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool is_link + if (obj->is_link) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // saturated bool is_readable + if (obj->is_readable) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // saturated bool is_writeable + if (obj->is_writeable) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void4 + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 4U); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += 4UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Response_0_1_deserialize_( + uavcan_file_GetInfo_Response_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // truncated uint40 size + out_obj->size = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 unix_timestamp_of_last_modification + out_obj->unix_timestamp_of_last_modification = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // saturated bool is_file_not_directory + if (offset_bits < capacity_bits) + { + out_obj->is_file_not_directory = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->is_file_not_directory = false; + } + offset_bits += 1U; + // saturated bool is_link + if (offset_bits < capacity_bits) + { + out_obj->is_link = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->is_link = false; + } + offset_bits += 1U; + // saturated bool is_readable + if (offset_bits < capacity_bits) + { + out_obj->is_readable = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->is_readable = false; + } + offset_bits += 1U; + // saturated bool is_writeable + if (offset_bits < capacity_bits) + { + out_obj->is_writeable = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->is_writeable = false; + } + offset_bits += 1U; + // void4 + offset_bits += 4; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_GetInfo_Response_0_1_initialize_(uavcan_file_GetInfo_Response_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_GetInfo_Response_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_GET_INFO_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_2.h b/components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_2.h new file mode 100644 index 0000000..9bc1a2a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/GetInfo_0_2.h @@ -0,0 +1,496 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.2.dsdl +// Generated at: 2024-09-11 21:29:53.242552 UTC +// Is deprecated: no +// Fixed port-ID: 405 +// Full name: uavcan.file.GetInfo +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_GET_INFO_0_2_INCLUDED_ +#define UAVCAN_FILE_GET_INFO_0_2_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/405.GetInfo.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_GetInfo_0_2_HAS_FIXED_PORT_ID_ true +#define uavcan_file_GetInfo_0_2_FIXED_PORT_ID_ 405U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.GetInfo.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_GetInfo_0_2_FULL_NAME_ "uavcan.file.GetInfo" +#define uavcan_file_GetInfo_0_2_FULL_NAME_AND_VERSION_ "uavcan.file.GetInfo.0.2" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.GetInfo.Request.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_GetInfo_Request_0_2_FULL_NAME_ "uavcan.file.GetInfo.Request" +#define uavcan_file_GetInfo_Request_0_2_FULL_NAME_AND_VERSION_ "uavcan.file.GetInfo.Request.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_GetInfo_Request_0_2_EXTENT_BYTES_ 300UL +#define uavcan_file_GetInfo_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 256UL +static_assert(uavcan_file_GetInfo_Request_0_2_EXTENT_BYTES_ >= uavcan_file_GetInfo_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Path.2.0 path + uavcan_file_Path_2_0 path; +} uavcan_file_GetInfo_Request_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_GetInfo_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Request_0_2_serialize_( + const uavcan_file_GetInfo_Request_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2048UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Path.2.0 path + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_file_Path_2_0_serialize_( + &obj->path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Request_0_2_deserialize_( + uavcan_file_GetInfo_Request_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Path.2.0 path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err2_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_GetInfo_Request_0_2_initialize_(uavcan_file_GetInfo_Request_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_GetInfo_Request_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.GetInfo.Response.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_GetInfo_Response_0_2_FULL_NAME_ "uavcan.file.GetInfo.Response" +#define uavcan_file_GetInfo_Response_0_2_FULL_NAME_AND_VERSION_ "uavcan.file.GetInfo.Response.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_GetInfo_Response_0_2_EXTENT_BYTES_ 48UL +#define uavcan_file_GetInfo_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 13UL +static_assert(uavcan_file_GetInfo_Response_0_2_EXTENT_BYTES_ >= uavcan_file_GetInfo_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; + + /// truncated uint40 size + uint64_t size; + + /// truncated uint40 unix_timestamp_of_last_modification + uint64_t unix_timestamp_of_last_modification; + + /// saturated bool is_file_not_directory + bool is_file_not_directory; + + /// saturated bool is_link + bool is_link; + + /// saturated bool is_readable + bool is_readable; + + /// saturated bool is_writeable + bool is_writeable; +} uavcan_file_GetInfo_Response_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_GetInfo_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Response_0_2_serialize_( + const uavcan_file_GetInfo_Response_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 104UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err3_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err3_ < 0) + { + return _err3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + { // truncated uint40 size + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->size, 40U); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += 40U; + } + { // truncated uint40 unix_timestamp_of_last_modification + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->unix_timestamp_of_last_modification, 40U); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 40U; + } + { // saturated bool is_file_not_directory + buffer[offset_bits / 8U] = obj->is_file_not_directory ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool is_link + if (obj->is_link) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // saturated bool is_readable + if (obj->is_readable) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // saturated bool is_writeable + if (obj->is_writeable) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void4 + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 4U); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += 4UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_GetInfo_Response_0_2_deserialize_( + uavcan_file_GetInfo_Response_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // truncated uint40 size + out_obj->size = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 unix_timestamp_of_last_modification + out_obj->unix_timestamp_of_last_modification = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // saturated bool is_file_not_directory + if (offset_bits < capacity_bits) + { + out_obj->is_file_not_directory = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->is_file_not_directory = false; + } + offset_bits += 1U; + // saturated bool is_link + if (offset_bits < capacity_bits) + { + out_obj->is_link = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->is_link = false; + } + offset_bits += 1U; + // saturated bool is_readable + if (offset_bits < capacity_bits) + { + out_obj->is_readable = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->is_readable = false; + } + offset_bits += 1U; + // saturated bool is_writeable + if (offset_bits < capacity_bits) + { + out_obj->is_writeable = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->is_writeable = false; + } + offset_bits += 1U; + // void4 + offset_bits += 4; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_GetInfo_Response_0_2_initialize_(uavcan_file_GetInfo_Response_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_GetInfo_Response_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_GET_INFO_0_2_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/List_0_1.h b/components/esp_nunavut/nunavut/uavcan/file/List_0_1.h new file mode 100644 index 0000000..8ea4fd8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/List_0_1.h @@ -0,0 +1,425 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.268251 UTC +// Is deprecated: yes +// Fixed port-ID: 406 +// Full name: uavcan.file.List +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_FILE_LIST_0_1_INCLUDED_ +#define UAVCAN_FILE_LIST_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_List_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_file_List_0_1_FIXED_PORT_ID_ 406U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.List.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_List_0_1_FULL_NAME_ "uavcan.file.List" +#define uavcan_file_List_0_1_FULL_NAME_AND_VERSION_ "uavcan.file.List.0.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.List.Request.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_List_Request_0_1_FULL_NAME_ "uavcan.file.List.Request" +#define uavcan_file_List_Request_0_1_FULL_NAME_AND_VERSION_ "uavcan.file.List.Request.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_List_Request_0_1_EXTENT_BYTES_ 300UL +#define uavcan_file_List_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 121UL +static_assert(uavcan_file_List_Request_0_1_EXTENT_BYTES_ >= uavcan_file_List_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint32 entry_index + uint32_t entry_index; + + /// uavcan.file.Path.1.0 directory_path + uavcan_file_Path_1_0 directory_path; +} uavcan_file_List_Request_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_List_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Request_0_1_serialize_( + const uavcan_file_List_Request_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 968UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 entry_index + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->entry_index, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + { // void32 + (void) memset(&buffer[offset_bits / 8U], 0, 4); + offset_bits += 32UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.1.0 directory_path + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_1_0_serialize_( + &obj->directory_path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Request_0_1_deserialize_( + uavcan_file_List_Request_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 entry_index + out_obj->entry_index = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // void32 + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 directory_path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->directory_path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_List_Request_0_1_initialize_(uavcan_file_List_Request_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_List_Request_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.List.Response.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_List_Response_0_1_FULL_NAME_ "uavcan.file.List.Response" +#define uavcan_file_List_Response_0_1_FULL_NAME_AND_VERSION_ "uavcan.file.List.Response.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_List_Response_0_1_EXTENT_BYTES_ 300UL +#define uavcan_file_List_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 117UL +static_assert(uavcan_file_List_Response_0_1_EXTENT_BYTES_ >= uavcan_file_List_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Path.1.0 entry_base_name + uavcan_file_Path_1_0 entry_base_name; +} uavcan_file_List_Response_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_List_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Response_0_1_serialize_( + const uavcan_file_List_Response_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 936UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // void32 + (void) memset(&buffer[offset_bits / 8U], 0, 4); + offset_bits += 32UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + { // uavcan.file.Path.1.0 entry_base_name + size_t _size_bytes2_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err6_ = uavcan_file_Path_1_0_serialize_( + &obj->entry_base_name, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Response_0_1_deserialize_( + uavcan_file_List_Response_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // void32 + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 entry_base_name + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->entry_base_name, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_List_Response_0_1_initialize_(uavcan_file_List_Response_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_List_Response_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_LIST_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/List_0_2.h b/components/esp_nunavut/nunavut/uavcan/file/List_0_2.h new file mode 100644 index 0000000..e0b419e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/List_0_2.h @@ -0,0 +1,416 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.2.dsdl +// Generated at: 2024-09-11 21:29:53.261032 UTC +// Is deprecated: no +// Fixed port-ID: 406 +// Full name: uavcan.file.List +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_LIST_0_2_INCLUDED_ +#define UAVCAN_FILE_LIST_0_2_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/406.List.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_List_0_2_HAS_FIXED_PORT_ID_ true +#define uavcan_file_List_0_2_FIXED_PORT_ID_ 406U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.List.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_List_0_2_FULL_NAME_ "uavcan.file.List" +#define uavcan_file_List_0_2_FULL_NAME_AND_VERSION_ "uavcan.file.List.0.2" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.List.Request.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_List_Request_0_2_FULL_NAME_ "uavcan.file.List.Request" +#define uavcan_file_List_Request_0_2_FULL_NAME_AND_VERSION_ "uavcan.file.List.Request.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_List_Request_0_2_EXTENT_BYTES_ 300UL +#define uavcan_file_List_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 264UL +static_assert(uavcan_file_List_Request_0_2_EXTENT_BYTES_ >= uavcan_file_List_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint32 entry_index + uint32_t entry_index; + + /// uavcan.file.Path.2.0 directory_path + uavcan_file_Path_2_0 directory_path; +} uavcan_file_List_Request_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_List_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Request_0_2_serialize_( + const uavcan_file_List_Request_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2112UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 entry_index + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->entry_index, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + { // void32 + (void) memset(&buffer[offset_bits / 8U], 0, 4); + offset_bits += 32UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.2.0 directory_path + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_2_0_serialize_( + &obj->directory_path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Request_0_2_deserialize_( + uavcan_file_List_Request_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 entry_index + out_obj->entry_index = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // void32 + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 directory_path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->directory_path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_List_Request_0_2_initialize_(uavcan_file_List_Request_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_List_Request_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.List.Response.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_List_Response_0_2_FULL_NAME_ "uavcan.file.List.Response" +#define uavcan_file_List_Response_0_2_FULL_NAME_AND_VERSION_ "uavcan.file.List.Response.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_List_Response_0_2_EXTENT_BYTES_ 300UL +#define uavcan_file_List_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 260UL +static_assert(uavcan_file_List_Response_0_2_EXTENT_BYTES_ >= uavcan_file_List_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Path.2.0 entry_base_name + uavcan_file_Path_2_0 entry_base_name; +} uavcan_file_List_Response_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_List_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Response_0_2_serialize_( + const uavcan_file_List_Response_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2080UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // void32 + (void) memset(&buffer[offset_bits / 8U], 0, 4); + offset_bits += 32UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + { // uavcan.file.Path.2.0 entry_base_name + size_t _size_bytes2_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err6_ = uavcan_file_Path_2_0_serialize_( + &obj->entry_base_name, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_List_Response_0_2_deserialize_( + uavcan_file_List_Response_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // void32 + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 entry_base_name + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->entry_base_name, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_List_Response_0_2_initialize_(uavcan_file_List_Response_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_List_Response_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_LIST_0_2_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Modify_1_0.h b/components/esp_nunavut/nunavut/uavcan/file/Modify_1_0.h new file mode 100644 index 0000000..0f1be26 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Modify_1_0.h @@ -0,0 +1,475 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.283243 UTC +// Is deprecated: yes +// Fixed port-ID: 407 +// Full name: uavcan.file.Modify +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_FILE_MODIFY_1_0_INCLUDED_ +#define UAVCAN_FILE_MODIFY_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_Modify_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_file_Modify_1_0_FIXED_PORT_ID_ 407U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Modify.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Modify_1_0_FULL_NAME_ "uavcan.file.Modify" +#define uavcan_file_Modify_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Modify.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Modify.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Modify_Request_1_0_FULL_NAME_ "uavcan.file.Modify.Request" +#define uavcan_file_Modify_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Modify.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Modify_Request_1_0_EXTENT_BYTES_ 600UL +#define uavcan_file_Modify_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 230UL +static_assert(uavcan_file_Modify_Request_1_0_EXTENT_BYTES_ >= uavcan_file_Modify_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated bool preserve_source + bool preserve_source; + + /// saturated bool overwrite_destination + bool overwrite_destination; + + /// uavcan.file.Path.1.0 source + uavcan_file_Path_1_0 source; + + /// uavcan.file.Path.1.0 destination + uavcan_file_Path_1_0 destination; +} uavcan_file_Modify_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Modify_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Request_1_0_serialize_( + const uavcan_file_Modify_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 1840UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated bool preserve_source + buffer[offset_bits / 8U] = obj->preserve_source ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool overwrite_destination + if (obj->overwrite_destination) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void30 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 30U); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 30UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.1.0 source + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_1_0_serialize_( + &obj->source, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.file.Path.1.0 destination + size_t _size_bytes1_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_file_Path_1_0_serialize_( + &obj->destination, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Request_1_0_deserialize_( + uavcan_file_Modify_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated bool preserve_source + if (offset_bits < capacity_bits) + { + out_obj->preserve_source = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->preserve_source = false; + } + offset_bits += 1U; + // saturated bool overwrite_destination + if (offset_bits < capacity_bits) + { + out_obj->overwrite_destination = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->overwrite_destination = false; + } + offset_bits += 1U; + // void30 + offset_bits += 30; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 source + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->source, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 destination + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->destination, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Modify_Request_1_0_initialize_(uavcan_file_Modify_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Modify_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Modify.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Modify_Response_1_0_FULL_NAME_ "uavcan.file.Modify.Response" +#define uavcan_file_Modify_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Modify.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Modify_Response_1_0_EXTENT_BYTES_ 48UL +#define uavcan_file_Modify_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_file_Modify_Response_1_0_EXTENT_BYTES_ >= uavcan_file_Modify_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; +} uavcan_file_Modify_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Modify_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Response_1_0_serialize_( + const uavcan_file_Modify_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes4_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err8_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err8_ < 0) + { + return _err8_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Response_1_0_deserialize_( + uavcan_file_Modify_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err10_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Modify_Response_1_0_initialize_(uavcan_file_Modify_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Modify_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_MODIFY_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Modify_1_1.h b/components/esp_nunavut/nunavut/uavcan/file/Modify_1_1.h new file mode 100644 index 0000000..d99ea57 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Modify_1_1.h @@ -0,0 +1,466 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.275217 UTC +// Is deprecated: no +// Fixed port-ID: 407 +// Full name: uavcan.file.Modify +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_MODIFY_1_1_INCLUDED_ +#define UAVCAN_FILE_MODIFY_1_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/407.Modify.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_Modify_1_1_HAS_FIXED_PORT_ID_ true +#define uavcan_file_Modify_1_1_FIXED_PORT_ID_ 407U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Modify.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Modify_1_1_FULL_NAME_ "uavcan.file.Modify" +#define uavcan_file_Modify_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Modify.1.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Modify.Request.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Modify_Request_1_1_FULL_NAME_ "uavcan.file.Modify.Request" +#define uavcan_file_Modify_Request_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Modify.Request.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Modify_Request_1_1_EXTENT_BYTES_ 600UL +#define uavcan_file_Modify_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 516UL +static_assert(uavcan_file_Modify_Request_1_1_EXTENT_BYTES_ >= uavcan_file_Modify_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated bool preserve_source + bool preserve_source; + + /// saturated bool overwrite_destination + bool overwrite_destination; + + /// uavcan.file.Path.2.0 source + uavcan_file_Path_2_0 source; + + /// uavcan.file.Path.2.0 destination + uavcan_file_Path_2_0 destination; +} uavcan_file_Modify_Request_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Modify_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Request_1_1_serialize_( + const uavcan_file_Modify_Request_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 4128UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated bool preserve_source + buffer[offset_bits / 8U] = obj->preserve_source ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool overwrite_destination + if (obj->overwrite_destination) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void30 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 30U); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 30UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.2.0 source + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_2_0_serialize_( + &obj->source, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.file.Path.2.0 destination + size_t _size_bytes1_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_file_Path_2_0_serialize_( + &obj->destination, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Request_1_1_deserialize_( + uavcan_file_Modify_Request_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated bool preserve_source + if (offset_bits < capacity_bits) + { + out_obj->preserve_source = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->preserve_source = false; + } + offset_bits += 1U; + // saturated bool overwrite_destination + if (offset_bits < capacity_bits) + { + out_obj->overwrite_destination = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->overwrite_destination = false; + } + offset_bits += 1U; + // void30 + offset_bits += 30; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 source + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->source, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 destination + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->destination, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Modify_Request_1_1_initialize_(uavcan_file_Modify_Request_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Modify_Request_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Modify.Response.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Modify_Response_1_1_FULL_NAME_ "uavcan.file.Modify.Response" +#define uavcan_file_Modify_Response_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Modify.Response.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Modify_Response_1_1_EXTENT_BYTES_ 48UL +#define uavcan_file_Modify_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_file_Modify_Response_1_1_EXTENT_BYTES_ >= uavcan_file_Modify_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; +} uavcan_file_Modify_Response_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Modify_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Response_1_1_serialize_( + const uavcan_file_Modify_Response_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes4_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err8_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err8_ < 0) + { + return _err8_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Modify_Response_1_1_deserialize_( + uavcan_file_Modify_Response_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err10_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Modify_Response_1_1_initialize_(uavcan_file_Modify_Response_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Modify_Response_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_MODIFY_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Path_1_0.h b/components/esp_nunavut/nunavut/uavcan/file/Path_1_0.h new file mode 100644 index 0000000..ecee6b7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Path_1_0.h @@ -0,0 +1,257 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.295102 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.file.Path +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_FILE_PATH_1_0_INCLUDED_ +#define UAVCAN_FILE_PATH_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_file_Path_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Path.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Path_1_0_FULL_NAME_ "uavcan.file.Path" +#define uavcan_file_Path_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Path.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Path_1_0_EXTENT_BYTES_ 113UL +#define uavcan_file_Path_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 113UL +static_assert(uavcan_file_Path_1_0_EXTENT_BYTES_ >= uavcan_file_Path_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 SEPARATOR = 47 +#define uavcan_file_Path_1_0_SEPARATOR (47U) + +/// saturated uint8 MAX_LENGTH = 112 +#define uavcan_file_Path_1_0_MAX_LENGTH (112U) + +/// Array metadata for: saturated uint8[<=112] path +#define uavcan_file_Path_1_0_path_ARRAY_CAPACITY_ 112U +#define uavcan_file_Path_1_0_path_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=112] path + struct /// Array address equivalence guarantee: &elements[0] == &path + { + uint8_t elements[uavcan_file_Path_1_0_path_ARRAY_CAPACITY_]; + size_t count; + } path; +} uavcan_file_Path_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Path_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Path_1_0_serialize_( + const uavcan_file_Path_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 904UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=112] path + if (obj->path.count > 112) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->path.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->path.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->path.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Path_1_0_deserialize_( + uavcan_file_Path_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=112] path + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->path.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->path.count = 0U; + } + offset_bits += 8U; + if (out_obj->path.count > 112U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->path.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->path.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->path.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Path_1_0_initialize_(uavcan_file_Path_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Path_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_PATH_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Path_2_0.h b/components/esp_nunavut/nunavut/uavcan/file/Path_2_0.h new file mode 100644 index 0000000..ad5e7c7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Path_2_0.h @@ -0,0 +1,248 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.2.0.dsdl +// Generated at: 2024-09-11 21:29:53.290992 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.file.Path +// Version: 2.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_PATH_2_0_INCLUDED_ +#define UAVCAN_FILE_PATH_2_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/Path.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_file_Path_2_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Path.2.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Path_2_0_FULL_NAME_ "uavcan.file.Path" +#define uavcan_file_Path_2_0_FULL_NAME_AND_VERSION_ "uavcan.file.Path.2.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Path_2_0_EXTENT_BYTES_ 256UL +#define uavcan_file_Path_2_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 256UL +static_assert(uavcan_file_Path_2_0_EXTENT_BYTES_ >= uavcan_file_Path_2_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 SEPARATOR = 47 +#define uavcan_file_Path_2_0_SEPARATOR (47U) + +/// saturated uint8 MAX_LENGTH = 255 +#define uavcan_file_Path_2_0_MAX_LENGTH (255U) + +/// Array metadata for: saturated uint8[<=255] path +#define uavcan_file_Path_2_0_path_ARRAY_CAPACITY_ 255U +#define uavcan_file_Path_2_0_path_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=255] path + struct /// Array address equivalence guarantee: &elements[0] == &path + { + uint8_t elements[uavcan_file_Path_2_0_path_ARRAY_CAPACITY_]; + size_t count; + } path; +} uavcan_file_Path_2_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Path_2_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Path_2_0_serialize_( + const uavcan_file_Path_2_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2048UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=255] path + if (obj->path.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->path.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->path.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->path.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Path_2_0_deserialize_( + uavcan_file_Path_2_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=255] path + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->path.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->path.count = 0U; + } + offset_bits += 8U; + if (out_obj->path.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->path.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->path.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->path.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Path_2_0_initialize_(uavcan_file_Path_2_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Path_2_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_PATH_2_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Read_1_0.h b/components/esp_nunavut/nunavut/uavcan/file/Read_1_0.h new file mode 100644 index 0000000..3237c1a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Read_1_0.h @@ -0,0 +1,452 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.306566 UTC +// Is deprecated: yes +// Fixed port-ID: 408 +// Full name: uavcan.file.Read +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_FILE_READ_1_0_INCLUDED_ +#define UAVCAN_FILE_READ_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_Read_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_file_Read_1_0_FIXED_PORT_ID_ 408U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Read.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Read_1_0_FULL_NAME_ "uavcan.file.Read" +#define uavcan_file_Read_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Read.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Read.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Read_Request_1_0_FULL_NAME_ "uavcan.file.Read.Request" +#define uavcan_file_Read_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Read.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Read_Request_1_0_EXTENT_BYTES_ 300UL +#define uavcan_file_Read_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 118UL +static_assert(uavcan_file_Read_Request_1_0_EXTENT_BYTES_ >= uavcan_file_Read_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// truncated uint40 offset + uint64_t offset; + + /// uavcan.file.Path.1.0 path + uavcan_file_Path_1_0 path; +} uavcan_file_Read_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Read_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Request_1_0_serialize_( + const uavcan_file_Read_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 944UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint40 offset + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->offset, 40U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 40U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.1.0 path + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_1_0_serialize_( + &obj->path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Request_1_0_deserialize_( + uavcan_file_Read_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint40 offset + out_obj->offset = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Read_Request_1_0_initialize_(uavcan_file_Read_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Read_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Read.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Read_Response_1_0_FULL_NAME_ "uavcan.file.Read.Response" +#define uavcan_file_Read_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Read.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Read_Response_1_0_EXTENT_BYTES_ 300UL +#define uavcan_file_Read_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 260UL +static_assert(uavcan_file_Read_Response_1_0_EXTENT_BYTES_ >= uavcan_file_Read_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=256] data +#define uavcan_file_Read_Response_1_0_data_ARRAY_CAPACITY_ 256U +#define uavcan_file_Read_Response_1_0_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; + + /// saturated uint8[<=256] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_file_Read_Response_1_0_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_file_Read_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Read_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Response_1_0_serialize_( + const uavcan_file_Read_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2080UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err5_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err5_ < 0) + { + return _err5_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=256] data + if (obj->data.count > 256) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->data.count, 16U); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Response_1_0_deserialize_( + uavcan_file_Read_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=256] data + // Array length prefix: truncated uint16 + out_obj->data.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->data.count > 256U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Read_Response_1_0_initialize_(uavcan_file_Read_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Read_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_READ_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Read_1_1.h b/components/esp_nunavut/nunavut/uavcan/file/Read_1_1.h new file mode 100644 index 0000000..79fd712 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Read_1_1.h @@ -0,0 +1,430 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.299225 UTC +// Is deprecated: no +// Fixed port-ID: 408 +// Full name: uavcan.file.Read +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_READ_1_1_INCLUDED_ +#define UAVCAN_FILE_READ_1_1_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/408.Read.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_Read_1_1_HAS_FIXED_PORT_ID_ true +#define uavcan_file_Read_1_1_FIXED_PORT_ID_ 408U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Read.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Read_1_1_FULL_NAME_ "uavcan.file.Read" +#define uavcan_file_Read_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Read.1.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Read.Request.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Read_Request_1_1_FULL_NAME_ "uavcan.file.Read.Request" +#define uavcan_file_Read_Request_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Read.Request.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Read_Request_1_1_EXTENT_BYTES_ 300UL +#define uavcan_file_Read_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 261UL +static_assert(uavcan_file_Read_Request_1_1_EXTENT_BYTES_ >= uavcan_file_Read_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// truncated uint40 offset + uint64_t offset; + + /// uavcan.file.Path.2.0 path + uavcan_file_Path_2_0 path; +} uavcan_file_Read_Request_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Read_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Request_1_1_serialize_( + const uavcan_file_Read_Request_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2088UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint40 offset + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->offset, 40U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 40U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.2.0 path + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_2_0_serialize_( + &obj->path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Request_1_1_deserialize_( + uavcan_file_Read_Request_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint40 offset + out_obj->offset = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Read_Request_1_1_initialize_(uavcan_file_Read_Request_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Read_Request_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Read.Response.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Read_Response_1_1_FULL_NAME_ "uavcan.file.Read.Response" +#define uavcan_file_Read_Response_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Read.Response.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Read_Response_1_1_EXTENT_BYTES_ 300UL +#define uavcan_file_Read_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 260UL +static_assert(uavcan_file_Read_Response_1_1_EXTENT_BYTES_ >= uavcan_file_Read_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; + + /// uavcan.primitive.Unstructured.1.0 data + uavcan_primitive_Unstructured_1_0 data; +} uavcan_file_Read_Response_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Read_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Response_1_1_serialize_( + const uavcan_file_Read_Response_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2080UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err5_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err5_ < 0) + { + return _err5_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + } + { // uavcan.primitive.Unstructured.1.0 data + size_t _size_bytes3_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err7_ = uavcan_primitive_Unstructured_1_0_serialize_( + &obj->data, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Read_Response_1_1_deserialize_( + uavcan_file_Read_Response_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err9_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.primitive.Unstructured.1.0 data + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err10_ = uavcan_primitive_Unstructured_1_0_deserialize_( + &out_obj->data, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Read_Response_1_1_initialize_(uavcan_file_Read_Response_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Read_Response_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_READ_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Write_1_0.h b/components/esp_nunavut/nunavut/uavcan/file/Write_1_0.h new file mode 100644 index 0000000..7339559 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Write_1_0.h @@ -0,0 +1,455 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.321152 UTC +// Is deprecated: yes +// Fixed port-ID: 409 +// Full name: uavcan.file.Write +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_FILE_WRITE_1_0_INCLUDED_ +#define UAVCAN_FILE_WRITE_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_Write_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_file_Write_1_0_FIXED_PORT_ID_ 409U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Write.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Write_1_0_FULL_NAME_ "uavcan.file.Write" +#define uavcan_file_Write_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Write.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Write.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Write_Request_1_0_FULL_NAME_ "uavcan.file.Write.Request" +#define uavcan_file_Write_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Write.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Write_Request_1_0_EXTENT_BYTES_ 600UL +#define uavcan_file_Write_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 311UL +static_assert(uavcan_file_Write_Request_1_0_EXTENT_BYTES_ >= uavcan_file_Write_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=192] data +#define uavcan_file_Write_Request_1_0_data_ARRAY_CAPACITY_ 192U +#define uavcan_file_Write_Request_1_0_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// truncated uint40 offset + uint64_t offset; + + /// uavcan.file.Path.1.0 path + uavcan_file_Path_1_0 path; + + /// saturated uint8[<=192] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_file_Write_Request_1_0_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_file_Write_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Write_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Request_1_0_serialize_( + const uavcan_file_Write_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2488UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint40 offset + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->offset, 40U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 40U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.1.0 path + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_1_0_serialize_( + &obj->path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=192] data + if (obj->data.count > 192) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->data.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Request_1_0_deserialize_( + uavcan_file_Write_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint40 offset + out_obj->offset = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 path + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_file_Path_1_0_deserialize_( + &out_obj->path, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=192] data + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.count = 0U; + } + offset_bits += 8U; + if (out_obj->data.count > 192U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Write_Request_1_0_initialize_(uavcan_file_Write_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Write_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Write.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Write_Response_1_0_FULL_NAME_ "uavcan.file.Write.Response" +#define uavcan_file_Write_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.file.Write.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Write_Response_1_0_EXTENT_BYTES_ 48UL +#define uavcan_file_Write_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_file_Write_Response_1_0_EXTENT_BYTES_ >= uavcan_file_Write_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; +} uavcan_file_Write_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Write_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Response_1_0_serialize_( + const uavcan_file_Write_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err5_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err5_ < 0) + { + return _err5_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Response_1_0_deserialize_( + uavcan_file_Write_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Write_Response_1_0_initialize_(uavcan_file_Write_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Write_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_WRITE_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/file/Write_1_1.h b/components/esp_nunavut/nunavut/uavcan/file/Write_1_1.h new file mode 100644 index 0000000..83f0f36 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/file/Write_1_1.h @@ -0,0 +1,430 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.314082 UTC +// Is deprecated: no +// Fixed port-ID: 409 +// Full name: uavcan.file.Write +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_FILE_WRITE_1_1_INCLUDED_ +#define UAVCAN_FILE_WRITE_1_1_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/file/409.Write.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_file_Write_1_1_HAS_FIXED_PORT_ID_ true +#define uavcan_file_Write_1_1_FIXED_PORT_ID_ 409U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Write.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Write_1_1_FULL_NAME_ "uavcan.file.Write" +#define uavcan_file_Write_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Write.1.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Write.Request.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Write_Request_1_1_FULL_NAME_ "uavcan.file.Write.Request" +#define uavcan_file_Write_Request_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Write.Request.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Write_Request_1_1_EXTENT_BYTES_ 600UL +#define uavcan_file_Write_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 519UL +static_assert(uavcan_file_Write_Request_1_1_EXTENT_BYTES_ >= uavcan_file_Write_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// truncated uint40 offset + uint64_t offset; + + /// uavcan.file.Path.2.0 path + uavcan_file_Path_2_0 path; + + /// uavcan.primitive.Unstructured.1.0 data + uavcan_primitive_Unstructured_1_0 data; +} uavcan_file_Write_Request_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Write_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Request_1_1_serialize_( + const uavcan_file_Write_Request_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 4152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint40 offset + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->offset, 40U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 40U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.file.Path.2.0 path + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_file_Path_2_0_serialize_( + &obj->path, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.primitive.Unstructured.1.0 data + size_t _size_bytes1_ = 258UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_primitive_Unstructured_1_0_serialize_( + &obj->data, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Request_1_1_deserialize_( + uavcan_file_Write_Request_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint40 offset + out_obj->offset = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 path + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_file_Path_2_0_deserialize_( + &out_obj->path, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.primitive.Unstructured.1.0 data + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_primitive_Unstructured_1_0_deserialize_( + &out_obj->data, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Write_Request_1_1_initialize_(uavcan_file_Write_Request_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Write_Request_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.file.Write.Response.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_file_Write_Response_1_1_FULL_NAME_ "uavcan.file.Write.Response" +#define uavcan_file_Write_Response_1_1_FULL_NAME_AND_VERSION_ "uavcan.file.Write.Response.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_file_Write_Response_1_1_EXTENT_BYTES_ 48UL +#define uavcan_file_Write_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_file_Write_Response_1_1_EXTENT_BYTES_ >= uavcan_file_Write_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.file.Error.1.0 error + uavcan_file_Error_1_0 _error; +} uavcan_file_Write_Response_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_file_Write_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Response_1_1_serialize_( + const uavcan_file_Write_Response_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.file.Error.1.0 error + size_t _size_bytes4_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err8_ = uavcan_file_Error_1_0_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err8_ < 0) + { + return _err8_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_file_Write_Response_1_1_deserialize_( + uavcan_file_Write_Response_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.file.Error.1.0 error + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err10_ = uavcan_file_Error_1_0_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_file_Write_Response_1_1_initialize_(uavcan_file_Write_Response_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_file_Write_Response_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_WRITE_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_1.h b/components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_1.h new file mode 100644 index 0000000..8b81300 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_1.h @@ -0,0 +1,369 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.511232 UTC +// Is deprecated: yes +// Fixed port-ID: 500 +// Full name: uavcan.internet.udp.HandleIncomingPacket +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_1_INCLUDED_ +#define UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_internet_udp_HandleIncomingPacket_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_internet_udp_HandleIncomingPacket_0_1_FIXED_PORT_ID_ 500U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.HandleIncomingPacket.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_HandleIncomingPacket_0_1_FULL_NAME_ "uavcan.internet.udp.HandleIncomingPacket" +#define uavcan_internet_udp_HandleIncomingPacket_0_1_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.HandleIncomingPacket.0.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.HandleIncomingPacket.Request.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_1_FULL_NAME_ "uavcan.internet.udp.HandleIncomingPacket.Request" +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_1_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.HandleIncomingPacket.Request.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_1_EXTENT_BYTES_ 600UL +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 313UL +static_assert(uavcan_internet_udp_HandleIncomingPacket_Request_0_1_EXTENT_BYTES_ >= uavcan_internet_udp_HandleIncomingPacket_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=309] payload +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_1_payload_ARRAY_CAPACITY_ 309U +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_1_payload_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 session_id + uint16_t session_id; + + /// saturated uint8[<=309] payload + struct /// Array address equivalence guarantee: &elements[0] == &payload + { + uint8_t elements[uavcan_internet_udp_HandleIncomingPacket_Request_0_1_payload_ARRAY_CAPACITY_]; + size_t count; + } payload; +} uavcan_internet_udp_HandleIncomingPacket_Request_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_internet_udp_HandleIncomingPacket_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Request_0_1_serialize_( + const uavcan_internet_udp_HandleIncomingPacket_Request_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2504UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 session_id + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->session_id, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint8[<=309] payload + if (obj->payload.count > 309) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->payload.count, 16U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->payload.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->payload.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Request_0_1_deserialize_( + uavcan_internet_udp_HandleIncomingPacket_Request_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 session_id + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=309] payload + // Array length prefix: truncated uint16 + out_obj->payload.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->payload.count > 309U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->payload.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->payload.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->payload.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_internet_udp_HandleIncomingPacket_Request_0_1_initialize_(uavcan_internet_udp_HandleIncomingPacket_Request_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_internet_udp_HandleIncomingPacket_Request_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.HandleIncomingPacket.Response.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_1_FULL_NAME_ "uavcan.internet.udp.HandleIncomingPacket.Response" +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_1_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.HandleIncomingPacket.Response.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_1_EXTENT_BYTES_ 63UL +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(uavcan_internet_udp_HandleIncomingPacket_Response_0_1_EXTENT_BYTES_ >= uavcan_internet_udp_HandleIncomingPacket_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_internet_udp_HandleIncomingPacket_Response_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_internet_udp_HandleIncomingPacket_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Response_0_1_serialize_( + const uavcan_internet_udp_HandleIncomingPacket_Response_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Response_0_1_deserialize_( + uavcan_internet_udp_HandleIncomingPacket_Response_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_internet_udp_HandleIncomingPacket_Response_0_1_initialize_(uavcan_internet_udp_HandleIncomingPacket_Response_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_internet_udp_HandleIncomingPacket_Response_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_2.h b/components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_2.h new file mode 100644 index 0000000..1b81ca9 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/internet/udp/HandleIncomingPacket_0_2.h @@ -0,0 +1,360 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl +// Generated at: 2024-09-11 21:29:53.505248 UTC +// Is deprecated: no +// Fixed port-ID: 500 +// Full name: uavcan.internet.udp.HandleIncomingPacket +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_2_INCLUDED_ +#define UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_2_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_internet_udp_HandleIncomingPacket_0_2_HAS_FIXED_PORT_ID_ true +#define uavcan_internet_udp_HandleIncomingPacket_0_2_FIXED_PORT_ID_ 500U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.HandleIncomingPacket.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_HandleIncomingPacket_0_2_FULL_NAME_ "uavcan.internet.udp.HandleIncomingPacket" +#define uavcan_internet_udp_HandleIncomingPacket_0_2_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.HandleIncomingPacket.0.2" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.HandleIncomingPacket.Request.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_2_FULL_NAME_ "uavcan.internet.udp.HandleIncomingPacket.Request" +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_2_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.HandleIncomingPacket.Request.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_2_EXTENT_BYTES_ 600UL +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 512UL +static_assert(uavcan_internet_udp_HandleIncomingPacket_Request_0_2_EXTENT_BYTES_ >= uavcan_internet_udp_HandleIncomingPacket_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=508] payload +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_2_payload_ARRAY_CAPACITY_ 508U +#define uavcan_internet_udp_HandleIncomingPacket_Request_0_2_payload_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 session_id + uint16_t session_id; + + /// saturated uint8[<=508] payload + struct /// Array address equivalence guarantee: &elements[0] == &payload + { + uint8_t elements[uavcan_internet_udp_HandleIncomingPacket_Request_0_2_payload_ARRAY_CAPACITY_]; + size_t count; + } payload; +} uavcan_internet_udp_HandleIncomingPacket_Request_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_internet_udp_HandleIncomingPacket_Request_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Request_0_2_serialize_( + const uavcan_internet_udp_HandleIncomingPacket_Request_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 4096UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 session_id + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->session_id, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint8[<=508] payload + if (obj->payload.count > 508) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->payload.count, 16U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->payload.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->payload.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Request_0_2_deserialize_( + uavcan_internet_udp_HandleIncomingPacket_Request_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 session_id + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=508] payload + // Array length prefix: truncated uint16 + out_obj->payload.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->payload.count > 508U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->payload.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->payload.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->payload.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_internet_udp_HandleIncomingPacket_Request_0_2_initialize_(uavcan_internet_udp_HandleIncomingPacket_Request_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_internet_udp_HandleIncomingPacket_Request_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.HandleIncomingPacket.Response.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_2_FULL_NAME_ "uavcan.internet.udp.HandleIncomingPacket.Response" +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_2_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.HandleIncomingPacket.Response.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_2_EXTENT_BYTES_ 63UL +#define uavcan_internet_udp_HandleIncomingPacket_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(uavcan_internet_udp_HandleIncomingPacket_Response_0_2_EXTENT_BYTES_ >= uavcan_internet_udp_HandleIncomingPacket_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_internet_udp_HandleIncomingPacket_Response_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_internet_udp_HandleIncomingPacket_Response_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Response_0_2_serialize_( + const uavcan_internet_udp_HandleIncomingPacket_Response_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_HandleIncomingPacket_Response_0_2_deserialize_( + uavcan_internet_udp_HandleIncomingPacket_Response_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_internet_udp_HandleIncomingPacket_Response_0_2_initialize_(uavcan_internet_udp_HandleIncomingPacket_Response_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_internet_udp_HandleIncomingPacket_Response_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_2_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_1.h b/components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_1.h new file mode 100644 index 0000000..d76ee5d --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_1.h @@ -0,0 +1,387 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.524235 UTC +// Is deprecated: yes +// Fixed port-ID: 8174 +// Full name: uavcan.internet.udp.OutgoingPacket +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_1_INCLUDED_ +#define UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_internet_udp_OutgoingPacket_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_internet_udp_OutgoingPacket_0_1_FIXED_PORT_ID_ 8174U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.OutgoingPacket.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_OutgoingPacket_0_1_FULL_NAME_ "uavcan.internet.udp.OutgoingPacket" +#define uavcan_internet_udp_OutgoingPacket_0_1_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.OutgoingPacket.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_internet_udp_OutgoingPacket_0_1_EXTENT_BYTES_ 600UL +#define uavcan_internet_udp_OutgoingPacket_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 313UL +static_assert(uavcan_internet_udp_OutgoingPacket_0_1_EXTENT_BYTES_ >= uavcan_internet_udp_OutgoingPacket_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint32 NAT_ENTRY_MIN_TTL = 86400 +#define uavcan_internet_udp_OutgoingPacket_0_1_NAT_ENTRY_MIN_TTL (86400UL) + +/// Array metadata for: saturated uint8[<=45] destination_address +#define uavcan_internet_udp_OutgoingPacket_0_1_destination_address_ARRAY_CAPACITY_ 45U +#define uavcan_internet_udp_OutgoingPacket_0_1_destination_address_ARRAY_IS_VARIABLE_LENGTH_ true + +/// Array metadata for: saturated uint8[<=260] payload +#define uavcan_internet_udp_OutgoingPacket_0_1_payload_ARRAY_CAPACITY_ 260U +#define uavcan_internet_udp_OutgoingPacket_0_1_payload_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 session_id + uint16_t session_id; + + /// saturated uint16 destination_port + uint16_t destination_port; + + /// saturated uint8[<=45] destination_address + struct /// Array address equivalence guarantee: &elements[0] == &destination_address + { + uint8_t elements[uavcan_internet_udp_OutgoingPacket_0_1_destination_address_ARRAY_CAPACITY_]; + size_t count; + } destination_address; + + /// saturated bool use_masquerading + bool use_masquerading; + + /// saturated bool use_dtls + bool use_dtls; + + /// saturated uint8[<=260] payload + struct /// Array address equivalence guarantee: &elements[0] == &payload + { + uint8_t elements[uavcan_internet_udp_OutgoingPacket_0_1_payload_ARRAY_CAPACITY_]; + size_t count; + } payload; +} uavcan_internet_udp_OutgoingPacket_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_internet_udp_OutgoingPacket_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_OutgoingPacket_0_1_serialize_( + const uavcan_internet_udp_OutgoingPacket_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2504UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 session_id + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->session_id, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint16 destination_port + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->destination_port, 16U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + { // saturated uint8[<=45] destination_address + if (obj->destination_address.count > 45) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->destination_address.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->destination_address.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->destination_address.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + { // saturated bool use_masquerading + buffer[offset_bits / 8U] = obj->use_masquerading ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool use_dtls + if (obj->use_dtls) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void6 + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 6U); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 6UL; + } + { // saturated uint8[<=260] payload + if (obj->payload.count > 260) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->payload.count, 16U); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += 16U; + for (size_t _index1_ = 0U; _index1_ < obj->payload.count; ++_index1_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->payload.elements[_index1_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_OutgoingPacket_0_1_deserialize_( + uavcan_internet_udp_OutgoingPacket_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 session_id + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint16 destination_port + out_obj->destination_port = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=45] destination_address + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->destination_address.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->destination_address.count = 0U; + } + offset_bits += 8U; + if (out_obj->destination_address.count > 45U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index2_ = 0U; _index2_ < out_obj->destination_address.count; ++_index2_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->destination_address.elements[_index2_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->destination_address.elements[_index2_] = 0U; + } + offset_bits += 8U; + } + // saturated bool use_masquerading + if (offset_bits < capacity_bits) + { + out_obj->use_masquerading = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->use_masquerading = false; + } + offset_bits += 1U; + // saturated bool use_dtls + if (offset_bits < capacity_bits) + { + out_obj->use_dtls = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->use_dtls = false; + } + offset_bits += 1U; + // void6 + offset_bits += 6; + // saturated uint8[<=260] payload + // Array length prefix: truncated uint16 + out_obj->payload.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->payload.count > 260U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index3_ = 0U; _index3_ < out_obj->payload.count; ++_index3_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->payload.elements[_index3_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->payload.elements[_index3_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_internet_udp_OutgoingPacket_0_1_initialize_(uavcan_internet_udp_OutgoingPacket_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_internet_udp_OutgoingPacket_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_2.h b/components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_2.h new file mode 100644 index 0000000..f51781c --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/internet/udp/OutgoingPacket_0_2.h @@ -0,0 +1,378 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl +// Generated at: 2024-09-11 21:29:53.516908 UTC +// Is deprecated: no +// Fixed port-ID: 8174 +// Full name: uavcan.internet.udp.OutgoingPacket +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_2_INCLUDED_ +#define UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_2_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_internet_udp_OutgoingPacket_0_2_HAS_FIXED_PORT_ID_ true +#define uavcan_internet_udp_OutgoingPacket_0_2_FIXED_PORT_ID_ 8174U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.internet.udp.OutgoingPacket.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_internet_udp_OutgoingPacket_0_2_FULL_NAME_ "uavcan.internet.udp.OutgoingPacket" +#define uavcan_internet_udp_OutgoingPacket_0_2_FULL_NAME_AND_VERSION_ "uavcan.internet.udp.OutgoingPacket.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_internet_udp_OutgoingPacket_0_2_EXTENT_BYTES_ 600UL +#define uavcan_internet_udp_OutgoingPacket_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 561UL +static_assert(uavcan_internet_udp_OutgoingPacket_0_2_EXTENT_BYTES_ >= uavcan_internet_udp_OutgoingPacket_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint32 NAT_ENTRY_MIN_TTL = 86400 +#define uavcan_internet_udp_OutgoingPacket_0_2_NAT_ENTRY_MIN_TTL (86400UL) + +/// Array metadata for: saturated uint8[<=45] destination_address +#define uavcan_internet_udp_OutgoingPacket_0_2_destination_address_ARRAY_CAPACITY_ 45U +#define uavcan_internet_udp_OutgoingPacket_0_2_destination_address_ARRAY_IS_VARIABLE_LENGTH_ true + +/// Array metadata for: saturated uint8[<=508] payload +#define uavcan_internet_udp_OutgoingPacket_0_2_payload_ARRAY_CAPACITY_ 508U +#define uavcan_internet_udp_OutgoingPacket_0_2_payload_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 session_id + uint16_t session_id; + + /// saturated uint16 destination_port + uint16_t destination_port; + + /// saturated uint8[<=45] destination_address + struct /// Array address equivalence guarantee: &elements[0] == &destination_address + { + uint8_t elements[uavcan_internet_udp_OutgoingPacket_0_2_destination_address_ARRAY_CAPACITY_]; + size_t count; + } destination_address; + + /// saturated bool use_masquerading + bool use_masquerading; + + /// saturated bool use_dtls + bool use_dtls; + + /// saturated uint8[<=508] payload + struct /// Array address equivalence guarantee: &elements[0] == &payload + { + uint8_t elements[uavcan_internet_udp_OutgoingPacket_0_2_payload_ARRAY_CAPACITY_]; + size_t count; + } payload; +} uavcan_internet_udp_OutgoingPacket_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_internet_udp_OutgoingPacket_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_OutgoingPacket_0_2_serialize_( + const uavcan_internet_udp_OutgoingPacket_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 4488UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 session_id + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->session_id, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint16 destination_port + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->destination_port, 16U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + { // saturated uint8[<=45] destination_address + if (obj->destination_address.count > 45) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->destination_address.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->destination_address.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->destination_address.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + { // saturated bool use_masquerading + buffer[offset_bits / 8U] = obj->use_masquerading ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool use_dtls + if (obj->use_dtls) + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] | (1U << (offset_bits % 8U))); + } + else + { + buffer[offset_bits / 8U] = (uint8_t)(buffer[offset_bits / 8U] & ~(1U << (offset_bits % 8U))); + } + offset_bits += 1U; + } + { // void6 + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 6U); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 6UL; + } + { // saturated uint8[<=508] payload + if (obj->payload.count > 508) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->payload.count, 16U); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += 16U; + for (size_t _index1_ = 0U; _index1_ < obj->payload.count; ++_index1_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->payload.elements[_index1_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_internet_udp_OutgoingPacket_0_2_deserialize_( + uavcan_internet_udp_OutgoingPacket_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 session_id + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint16 destination_port + out_obj->destination_port = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=45] destination_address + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->destination_address.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->destination_address.count = 0U; + } + offset_bits += 8U; + if (out_obj->destination_address.count > 45U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index2_ = 0U; _index2_ < out_obj->destination_address.count; ++_index2_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->destination_address.elements[_index2_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->destination_address.elements[_index2_] = 0U; + } + offset_bits += 8U; + } + // saturated bool use_masquerading + if (offset_bits < capacity_bits) + { + out_obj->use_masquerading = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->use_masquerading = false; + } + offset_bits += 1U; + // saturated bool use_dtls + if (offset_bits < capacity_bits) + { + out_obj->use_dtls = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->use_dtls = false; + } + offset_bits += 1U; + // void6 + offset_bits += 6; + // saturated uint8[<=508] payload + // Array length prefix: truncated uint16 + out_obj->payload.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->payload.count > 508U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index3_ = 0U; _index3_ < out_obj->payload.count; ++_index3_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->payload.elements[_index3_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->payload.elements[_index3_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_internet_udp_OutgoingPacket_0_2_initialize_(uavcan_internet_udp_OutgoingPacket_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_internet_udp_OutgoingPacket_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_2_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/ArbitrationID_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/ArbitrationID_0_1.h new file mode 100644 index 0000000..5267c0b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/ArbitrationID_0_1.h @@ -0,0 +1,306 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ArbitrationID.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.048358 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.ArbitrationID +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_ARBITRATION_ID_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_ARBITRATION_ID_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_ArbitrationID_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.ArbitrationID.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_ArbitrationID_0_1_FULL_NAME_ "uavcan.metatransport.can.ArbitrationID" +#define uavcan_metatransport_can_ArbitrationID_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.ArbitrationID.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_ArbitrationID_0_1_EXTENT_BYTES_ 5UL +#define uavcan_metatransport_can_ArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 5UL +static_assert(uavcan_metatransport_can_ArbitrationID_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_ArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// uavcan.metatransport.can.BaseArbitrationID.0.1 base + uavcan_metatransport_can_BaseArbitrationID_0_1 base; + + /// uavcan.metatransport.can.ExtendedArbitrationID.0.1 extended + uavcan_metatransport_can_ExtendedArbitrationID_0_1 extended; + }; + uint8_t _tag_; +} uavcan_metatransport_can_ArbitrationID_0_1; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_metatransport_can_ArbitrationID_0_1_UNION_OPTION_COUNT_ 2U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_ArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_ArbitrationID_0_1_serialize_( + const uavcan_metatransport_can_ArbitrationID_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 40UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // uavcan.metatransport.can.BaseArbitrationID.0.1 base + { + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_metatransport_can_BaseArbitrationID_0_1_serialize_( + &obj->base, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + else if (1U == obj->_tag_) // uavcan.metatransport.can.ExtendedArbitrationID.0.1 extended + { + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_metatransport_can_ExtendedArbitrationID_0_1_serialize_( + &obj->extended, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_ArbitrationID_0_1_deserialize_( + uavcan_metatransport_can_ArbitrationID_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // uavcan.metatransport.can.BaseArbitrationID.0.1 base + { + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_metatransport_can_BaseArbitrationID_0_1_deserialize_( + &out_obj->base, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (1U == out_obj->_tag_) // uavcan.metatransport.can.ExtendedArbitrationID.0.1 extended + { + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_metatransport_can_ExtendedArbitrationID_0_1_deserialize_( + &out_obj->extended, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_ArbitrationID_0_1_initialize_(uavcan_metatransport_can_ArbitrationID_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_ArbitrationID_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "base" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_ArbitrationID_0_1_select_base_(uavcan_metatransport_can_ArbitrationID_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "base" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_ArbitrationID_0_1_is_base_(const uavcan_metatransport_can_ArbitrationID_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "extended" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_ArbitrationID_0_1_select_extended_(uavcan_metatransport_can_ArbitrationID_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "extended" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_ArbitrationID_0_1_is_extended_(const uavcan_metatransport_can_ArbitrationID_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_ARBITRATION_ID_0_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/BaseArbitrationID_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/BaseArbitrationID_0_1.h new file mode 100644 index 0000000..ad098d4 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/BaseArbitrationID_0_1.h @@ -0,0 +1,213 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.053732 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.BaseArbitrationID +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_BASE_ARBITRATION_ID_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_BASE_ARBITRATION_ID_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_BaseArbitrationID_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.BaseArbitrationID.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_BaseArbitrationID_0_1_FULL_NAME_ "uavcan.metatransport.can.BaseArbitrationID" +#define uavcan_metatransport_can_BaseArbitrationID_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.BaseArbitrationID.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_BaseArbitrationID_0_1_EXTENT_BYTES_ 4UL +#define uavcan_metatransport_can_BaseArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_metatransport_can_BaseArbitrationID_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_BaseArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// truncated uint11 value + uint16_t value; +} uavcan_metatransport_can_BaseArbitrationID_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_BaseArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_BaseArbitrationID_0_1_serialize_( + const uavcan_metatransport_can_BaseArbitrationID_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint11 value + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 11U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 11U; + } + { // void21 + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 21U); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 21UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_BaseArbitrationID_0_1_deserialize_( + uavcan_metatransport_can_BaseArbitrationID_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint11 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 11); + offset_bits += 11U; + // void21 + offset_bits += 21; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_BaseArbitrationID_0_1_initialize_(uavcan_metatransport_can_BaseArbitrationID_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_BaseArbitrationID_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_BASE_ARBITRATION_ID_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/DataClassic_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/DataClassic_0_1.h new file mode 100644 index 0000000..0077ec1 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/DataClassic_0_1.h @@ -0,0 +1,268 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataClassic.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.057437 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.DataClassic +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_DATA_CLASSIC_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_DATA_CLASSIC_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataClassic.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataClassic.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataClassic.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataClassic.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataClassic.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_DataClassic_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.DataClassic.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_DataClassic_0_1_FULL_NAME_ "uavcan.metatransport.can.DataClassic" +#define uavcan_metatransport_can_DataClassic_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.DataClassic.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_DataClassic_0_1_EXTENT_BYTES_ 14UL +#define uavcan_metatransport_can_DataClassic_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 14UL +static_assert(uavcan_metatransport_can_DataClassic_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_DataClassic_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=8] data +#define uavcan_metatransport_can_DataClassic_0_1_data_ARRAY_CAPACITY_ 8U +#define uavcan_metatransport_can_DataClassic_0_1_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + uavcan_metatransport_can_ArbitrationID_0_1 arbitration_id; + + /// saturated uint8[<=8] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_metatransport_can_DataClassic_0_1_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_metatransport_can_DataClassic_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_DataClassic_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_DataClassic_0_1_serialize_( + const uavcan_metatransport_can_DataClassic_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 112UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + size_t _size_bytes0_ = 5UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_metatransport_can_ArbitrationID_0_1_serialize_( + &obj->arbitration_id, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=8] data + if (obj->data.count > 8) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->data.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_DataClassic_0_1_deserialize_( + uavcan_metatransport_can_DataClassic_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err2_ = uavcan_metatransport_can_ArbitrationID_0_1_deserialize_( + &out_obj->arbitration_id, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=8] data + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.count = 0U; + } + offset_bits += 8U; + if (out_obj->data.count > 8U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_DataClassic_0_1_initialize_(uavcan_metatransport_can_DataClassic_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_DataClassic_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_DATA_CLASSIC_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/DataFD_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/DataFD_0_1.h new file mode 100644 index 0000000..10fa925 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/DataFD_0_1.h @@ -0,0 +1,268 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataFD.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.063073 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.DataFD +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_DATA_FD_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_DATA_FD_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataFD.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataFD.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataFD.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataFD.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/DataFD.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_DataFD_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.DataFD.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_DataFD_0_1_FULL_NAME_ "uavcan.metatransport.can.DataFD" +#define uavcan_metatransport_can_DataFD_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.DataFD.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_DataFD_0_1_EXTENT_BYTES_ 70UL +#define uavcan_metatransport_can_DataFD_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 70UL +static_assert(uavcan_metatransport_can_DataFD_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_DataFD_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=64] data +#define uavcan_metatransport_can_DataFD_0_1_data_ARRAY_CAPACITY_ 64U +#define uavcan_metatransport_can_DataFD_0_1_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + uavcan_metatransport_can_ArbitrationID_0_1 arbitration_id; + + /// saturated uint8[<=64] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_metatransport_can_DataFD_0_1_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_metatransport_can_DataFD_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_DataFD_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_DataFD_0_1_serialize_( + const uavcan_metatransport_can_DataFD_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 560UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + size_t _size_bytes0_ = 5UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_metatransport_can_ArbitrationID_0_1_serialize_( + &obj->arbitration_id, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=64] data + if (obj->data.count > 64) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->data.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_DataFD_0_1_deserialize_( + uavcan_metatransport_can_DataFD_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err2_ = uavcan_metatransport_can_ArbitrationID_0_1_deserialize_( + &out_obj->arbitration_id, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=64] data + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.count = 0U; + } + offset_bits += 8U; + if (out_obj->data.count > 64U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_DataFD_0_1_initialize_(uavcan_metatransport_can_DataFD_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_DataFD_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_DATA_FD_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/Error_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Error_0_1.h new file mode 100644 index 0000000..71ac728 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Error_0_1.h @@ -0,0 +1,196 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Error.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.068569 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Error +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_ERROR_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_ERROR_0_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Error.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Error.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Error.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Error.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Error.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_Error_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.Error.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_Error_0_1_FULL_NAME_ "uavcan.metatransport.can.Error" +#define uavcan_metatransport_can_Error_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.Error.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_Error_0_1_EXTENT_BYTES_ 4UL +#define uavcan_metatransport_can_Error_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_metatransport_can_Error_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_Error_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_metatransport_can_Error_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_Error_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Error_0_1_serialize_( + const uavcan_metatransport_can_Error_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // void32 + (void) memset(&buffer[offset_bits / 8U], 0, 4); + offset_bits += 32UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Error_0_1_deserialize_( + uavcan_metatransport_can_Error_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // void32 + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_Error_0_1_initialize_(uavcan_metatransport_can_Error_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_Error_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_ERROR_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/ExtendedArbitrationID_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/ExtendedArbitrationID_0_1.h new file mode 100644 index 0000000..5f922d7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/ExtendedArbitrationID_0_1.h @@ -0,0 +1,213 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.072206 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.ExtendedArbitrationID +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_EXTENDED_ARBITRATION_ID_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_EXTENDED_ARBITRATION_ID_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_ExtendedArbitrationID_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.ExtendedArbitrationID.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_ExtendedArbitrationID_0_1_FULL_NAME_ "uavcan.metatransport.can.ExtendedArbitrationID" +#define uavcan_metatransport_can_ExtendedArbitrationID_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.ExtendedArbitrationID.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_ExtendedArbitrationID_0_1_EXTENT_BYTES_ 4UL +#define uavcan_metatransport_can_ExtendedArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_metatransport_can_ExtendedArbitrationID_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_ExtendedArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// truncated uint29 value + uint32_t value; +} uavcan_metatransport_can_ExtendedArbitrationID_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_ExtendedArbitrationID_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_ExtendedArbitrationID_0_1_serialize_( + const uavcan_metatransport_can_ExtendedArbitrationID_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint29 value + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 29U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 29U; + } + { // void3 + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 3U); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 3UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_ExtendedArbitrationID_0_1_deserialize_( + uavcan_metatransport_can_ExtendedArbitrationID_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint29 value + out_obj->value = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 29); + offset_bits += 29U; + // void3 + offset_bits += 3; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_ExtendedArbitrationID_0_1_initialize_(uavcan_metatransport_can_ExtendedArbitrationID_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_ExtendedArbitrationID_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_EXTENDED_ARBITRATION_ID_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_1.h new file mode 100644 index 0000000..0e17148 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_1.h @@ -0,0 +1,260 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.082941 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Frame +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_METATRANSPORT_CAN_FRAME_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_FRAME_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_Frame_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.Frame.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_Frame_0_1_FULL_NAME_ "uavcan.metatransport.can.Frame" +#define uavcan_metatransport_can_Frame_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.Frame.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_Frame_0_1_EXTENT_BYTES_ 78UL +#define uavcan_metatransport_can_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 78UL +static_assert(uavcan_metatransport_can_Frame_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// uavcan.metatransport.can.Manifestation.0.1 manifestation + uavcan_metatransport_can_Manifestation_0_1 manifestation; +} uavcan_metatransport_can_Frame_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Frame_0_1_serialize_( + const uavcan_metatransport_can_Frame_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 624UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.metatransport.can.Manifestation.0.1 manifestation + size_t _size_bytes1_ = 71UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_metatransport_can_Manifestation_0_1_serialize_( + &obj->manifestation, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Frame_0_1_deserialize_( + uavcan_metatransport_can_Frame_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.metatransport.can.Manifestation.0.1 manifestation + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_metatransport_can_Manifestation_0_1_deserialize_( + &out_obj->manifestation, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_Frame_0_1_initialize_(uavcan_metatransport_can_Frame_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_Frame_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_FRAME_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_2.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_2.h new file mode 100644 index 0000000..bb10123 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Frame_0_2.h @@ -0,0 +1,394 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.2.dsdl +// Generated at: 2024-09-11 21:29:54.075985 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Frame +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_FRAME_0_2_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_FRAME_0_2_INCLUDED_ + +#include +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Frame.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_Frame_0_2_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.Frame.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_Frame_0_2_FULL_NAME_ "uavcan.metatransport.can.Frame" +#define uavcan_metatransport_can_Frame_0_2_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.Frame.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_Frame_0_2_EXTENT_BYTES_ 71UL +#define uavcan_metatransport_can_Frame_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 71UL +static_assert(uavcan_metatransport_can_Frame_0_2_EXTENT_BYTES_ >= uavcan_metatransport_can_Frame_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// uavcan.metatransport.can.Error.0.1 error + uavcan_metatransport_can_Error_0_1 _error; + + /// uavcan.metatransport.can.DataFD.0.1 data_fd + uavcan_metatransport_can_DataFD_0_1 data_fd; + + /// uavcan.metatransport.can.DataClassic.0.1 data_classic + uavcan_metatransport_can_DataClassic_0_1 data_classic; + + /// uavcan.metatransport.can.RTR.0.1 remote_transmission_request + uavcan_metatransport_can_RTR_0_1 remote_transmission_request; + }; + uint8_t _tag_; +} uavcan_metatransport_can_Frame_0_2; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_metatransport_can_Frame_0_2_UNION_OPTION_COUNT_ 4U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_Frame_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Frame_0_2_serialize_( + const uavcan_metatransport_can_Frame_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 568UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // uavcan.metatransport.can.Error.0.1 error + { + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_metatransport_can_Error_0_1_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + else if (1U == obj->_tag_) // uavcan.metatransport.can.DataFD.0.1 data_fd + { + size_t _size_bytes1_ = 70UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_metatransport_can_DataFD_0_1_serialize_( + &obj->data_fd, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else if (2U == obj->_tag_) // uavcan.metatransport.can.DataClassic.0.1 data_classic + { + size_t _size_bytes2_ = 14UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_metatransport_can_DataClassic_0_1_serialize_( + &obj->data_classic, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + else if (3U == obj->_tag_) // uavcan.metatransport.can.RTR.0.1 remote_transmission_request + { + size_t _size_bytes3_ = 5UL; // Nested object (max) size, in bytes. + int8_t _err3_ = uavcan_metatransport_can_RTR_0_1_serialize_( + &obj->remote_transmission_request, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err3_ < 0) + { + return _err3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Frame_0_2_deserialize_( + uavcan_metatransport_can_Frame_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // uavcan.metatransport.can.Error.0.1 error + { + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_metatransport_can_Error_0_1_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (1U == out_obj->_tag_) // uavcan.metatransport.can.DataFD.0.1 data_fd + { + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_metatransport_can_DataFD_0_1_deserialize_( + &out_obj->data_fd, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (2U == out_obj->_tag_) // uavcan.metatransport.can.DataClassic.0.1 data_classic + { + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_metatransport_can_DataClassic_0_1_deserialize_( + &out_obj->data_classic, &buffer[offset_bits / 8U], &_size_bytes6_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes6_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (3U == out_obj->_tag_) // uavcan.metatransport.can.RTR.0.1 remote_transmission_request + { + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_metatransport_can_RTR_0_1_deserialize_( + &out_obj->remote_transmission_request, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes7_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_Frame_0_2_initialize_(uavcan_metatransport_can_Frame_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_Frame_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "error" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Frame_0_2_select_error_(uavcan_metatransport_can_Frame_0_2* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "error" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Frame_0_2_is_error_(const uavcan_metatransport_can_Frame_0_2* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "data_fd" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Frame_0_2_select_data_fd_(uavcan_metatransport_can_Frame_0_2* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "data_fd" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Frame_0_2_is_data_fd_(const uavcan_metatransport_can_Frame_0_2* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +/// Mark option "data_classic" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Frame_0_2_select_data_classic_(uavcan_metatransport_can_Frame_0_2* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 2; + } +} + +/// Check if option "data_classic" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Frame_0_2_is_data_classic_(const uavcan_metatransport_can_Frame_0_2* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 2)); +} + +/// Mark option "remote_transmission_request" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Frame_0_2_select_remote_transmission_request_(uavcan_metatransport_can_Frame_0_2* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 3; + } +} + +/// Check if option "remote_transmission_request" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Frame_0_2_is_remote_transmission_request_(const uavcan_metatransport_can_Frame_0_2* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 3)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_FRAME_0_2_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/Manifestation_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Manifestation_0_1.h new file mode 100644 index 0000000..fdb25ee --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/Manifestation_0_1.h @@ -0,0 +1,403 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Manifestation.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.087981 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Manifestation +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_METATRANSPORT_CAN_MANIFESTATION_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_MANIFESTATION_0_1_INCLUDED_ + +#include +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Manifestation.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Manifestation.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Manifestation.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Manifestation.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/Manifestation.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_Manifestation_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.Manifestation.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_Manifestation_0_1_FULL_NAME_ "uavcan.metatransport.can.Manifestation" +#define uavcan_metatransport_can_Manifestation_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.Manifestation.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_Manifestation_0_1_EXTENT_BYTES_ 71UL +#define uavcan_metatransport_can_Manifestation_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 71UL +static_assert(uavcan_metatransport_can_Manifestation_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_Manifestation_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// uavcan.metatransport.can.Error.0.1 error + uavcan_metatransport_can_Error_0_1 _error; + + /// uavcan.metatransport.can.DataFD.0.1 data_fd + uavcan_metatransport_can_DataFD_0_1 data_fd; + + /// uavcan.metatransport.can.DataClassic.0.1 data_classic + uavcan_metatransport_can_DataClassic_0_1 data_classic; + + /// uavcan.metatransport.can.RTR.0.1 remote_transmission_request + uavcan_metatransport_can_RTR_0_1 remote_transmission_request; + }; + uint8_t _tag_; +} uavcan_metatransport_can_Manifestation_0_1; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_metatransport_can_Manifestation_0_1_UNION_OPTION_COUNT_ 4U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_Manifestation_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Manifestation_0_1_serialize_( + const uavcan_metatransport_can_Manifestation_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 568UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // uavcan.metatransport.can.Error.0.1 error + { + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_metatransport_can_Error_0_1_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + else if (1U == obj->_tag_) // uavcan.metatransport.can.DataFD.0.1 data_fd + { + size_t _size_bytes1_ = 70UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_metatransport_can_DataFD_0_1_serialize_( + &obj->data_fd, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else if (2U == obj->_tag_) // uavcan.metatransport.can.DataClassic.0.1 data_classic + { + size_t _size_bytes2_ = 14UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_metatransport_can_DataClassic_0_1_serialize_( + &obj->data_classic, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + else if (3U == obj->_tag_) // uavcan.metatransport.can.RTR.0.1 remote_transmission_request + { + size_t _size_bytes3_ = 5UL; // Nested object (max) size, in bytes. + int8_t _err3_ = uavcan_metatransport_can_RTR_0_1_serialize_( + &obj->remote_transmission_request, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err3_ < 0) + { + return _err3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_Manifestation_0_1_deserialize_( + uavcan_metatransport_can_Manifestation_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // uavcan.metatransport.can.Error.0.1 error + { + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_metatransport_can_Error_0_1_deserialize_( + &out_obj->_error, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (1U == out_obj->_tag_) // uavcan.metatransport.can.DataFD.0.1 data_fd + { + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_metatransport_can_DataFD_0_1_deserialize_( + &out_obj->data_fd, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (2U == out_obj->_tag_) // uavcan.metatransport.can.DataClassic.0.1 data_classic + { + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_metatransport_can_DataClassic_0_1_deserialize_( + &out_obj->data_classic, &buffer[offset_bits / 8U], &_size_bytes6_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes6_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (3U == out_obj->_tag_) // uavcan.metatransport.can.RTR.0.1 remote_transmission_request + { + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_metatransport_can_RTR_0_1_deserialize_( + &out_obj->remote_transmission_request, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes7_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_Manifestation_0_1_initialize_(uavcan_metatransport_can_Manifestation_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_Manifestation_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "error" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Manifestation_0_1_select_error_(uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "error" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Manifestation_0_1_is_error_(const uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "data_fd" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Manifestation_0_1_select_data_fd_(uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "data_fd" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Manifestation_0_1_is_data_fd_(const uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +/// Mark option "data_classic" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Manifestation_0_1_select_data_classic_(uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 2; + } +} + +/// Check if option "data_classic" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Manifestation_0_1_is_data_classic_(const uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 2)); +} + +/// Mark option "remote_transmission_request" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_metatransport_can_Manifestation_0_1_select_remote_transmission_request_(uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 3; + } +} + +/// Check if option "remote_transmission_request" is active. Returns false if @param obj is NULL. +static inline bool uavcan_metatransport_can_Manifestation_0_1_is_remote_transmission_request_(const uavcan_metatransport_can_Manifestation_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 3)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_MANIFESTATION_0_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/can/RTR_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/can/RTR_0_1.h new file mode 100644 index 0000000..c12bdab --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/can/RTR_0_1.h @@ -0,0 +1,214 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/RTR.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.095105 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.RTR +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_CAN_RTR_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_CAN_RTR_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/RTR.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/RTR.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/RTR.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/RTR.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/can/RTR.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_can_RTR_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.can.RTR.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_can_RTR_0_1_FULL_NAME_ "uavcan.metatransport.can.RTR" +#define uavcan_metatransport_can_RTR_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.can.RTR.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_can_RTR_0_1_EXTENT_BYTES_ 5UL +#define uavcan_metatransport_can_RTR_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 5UL +static_assert(uavcan_metatransport_can_RTR_0_1_EXTENT_BYTES_ >= uavcan_metatransport_can_RTR_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + uavcan_metatransport_can_ArbitrationID_0_1 arbitration_id; +} uavcan_metatransport_can_RTR_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_can_RTR_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_RTR_0_1_serialize_( + const uavcan_metatransport_can_RTR_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 40UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + size_t _size_bytes0_ = 5UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_metatransport_can_ArbitrationID_0_1_serialize_( + &obj->arbitration_id, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_can_RTR_0_1_deserialize_( + uavcan_metatransport_can_RTR_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.metatransport.can.ArbitrationID.0.1 arbitration_id + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err2_ = uavcan_metatransport_can_ArbitrationID_0_1_deserialize_( + &out_obj->arbitration_id, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_can_RTR_0_1_initialize_(uavcan_metatransport_can_RTR_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_can_RTR_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_RTR_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/EtherType_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/EtherType_0_1.h new file mode 100644 index 0000000..8cf3850 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/EtherType_0_1.h @@ -0,0 +1,213 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/EtherType.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.013866 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.ethernet.EtherType +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_ETHERNET_ETHER_TYPE_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_ETHERNET_ETHER_TYPE_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/EtherType.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/EtherType.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/EtherType.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/EtherType.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/EtherType.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_ethernet_EtherType_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.ethernet.EtherType.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_ethernet_EtherType_0_1_FULL_NAME_ "uavcan.metatransport.ethernet.EtherType" +#define uavcan_metatransport_ethernet_EtherType_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.ethernet.EtherType.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_ethernet_EtherType_0_1_EXTENT_BYTES_ 2UL +#define uavcan_metatransport_ethernet_EtherType_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_metatransport_ethernet_EtherType_0_1_EXTENT_BYTES_ >= uavcan_metatransport_ethernet_EtherType_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 IP_V4 = 2048 +#define uavcan_metatransport_ethernet_EtherType_0_1_IP_V4 (2048U) + +/// saturated uint16 ARP = 2054 +#define uavcan_metatransport_ethernet_EtherType_0_1_ARP (2054U) + +/// saturated uint16 IP_V6 = 34525 +#define uavcan_metatransport_ethernet_EtherType_0_1_IP_V6 (34525U) + +typedef struct +{ + /// saturated uint16 value + uint16_t value; +} uavcan_metatransport_ethernet_EtherType_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_ethernet_EtherType_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_ethernet_EtherType_0_1_serialize_( + const uavcan_metatransport_ethernet_EtherType_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_ethernet_EtherType_0_1_deserialize_( + uavcan_metatransport_ethernet_EtherType_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_ethernet_EtherType_0_1_initialize_(uavcan_metatransport_ethernet_EtherType_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_ethernet_EtherType_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_ETHERNET_ETHER_TYPE_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/Frame_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/Frame_0_1.h new file mode 100644 index 0000000..6de635f --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/ethernet/Frame_0_1.h @@ -0,0 +1,339 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/Frame.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.017601 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.ethernet.Frame +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_ETHERNET_FRAME_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_ETHERNET_FRAME_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/ethernet/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_ethernet_Frame_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.ethernet.Frame.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_ethernet_Frame_0_1_FULL_NAME_ "uavcan.metatransport.ethernet.Frame" +#define uavcan_metatransport_ethernet_Frame_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.ethernet.Frame.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_ethernet_Frame_0_1_EXTENT_BYTES_ 9232UL +#define uavcan_metatransport_ethernet_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 9232UL +static_assert(uavcan_metatransport_ethernet_Frame_0_1_EXTENT_BYTES_ >= uavcan_metatransport_ethernet_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[6] destination +#define uavcan_metatransport_ethernet_Frame_0_1_destination_ARRAY_CAPACITY_ 6U +#define uavcan_metatransport_ethernet_Frame_0_1_destination_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: saturated uint8[6] source +#define uavcan_metatransport_ethernet_Frame_0_1_source_ARRAY_CAPACITY_ 6U +#define uavcan_metatransport_ethernet_Frame_0_1_source_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: saturated uint8[<=9216] payload +#define uavcan_metatransport_ethernet_Frame_0_1_payload_ARRAY_CAPACITY_ 9216U +#define uavcan_metatransport_ethernet_Frame_0_1_payload_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[6] destination + uint8_t destination[6]; + + /// saturated uint8[6] source + uint8_t source[6]; + + /// uavcan.metatransport.ethernet.EtherType.0.1 ethertype + uavcan_metatransport_ethernet_EtherType_0_1 ethertype; + + /// saturated uint8[<=9216] payload + struct /// Array address equivalence guarantee: &elements[0] == &payload + { + uint8_t elements[uavcan_metatransport_ethernet_Frame_0_1_payload_ARRAY_CAPACITY_]; + size_t count; + } payload; +} uavcan_metatransport_ethernet_Frame_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_ethernet_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_ethernet_Frame_0_1_serialize_( + const uavcan_metatransport_ethernet_Frame_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 73856UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[6] destination + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->destination[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + { // saturated uint8[6] source + const size_t _origin1_ = offset_bits; + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->source[_index1_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin1_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + { // uavcan.metatransport.ethernet.EtherType.0.1 ethertype + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_metatransport_ethernet_EtherType_0_1_serialize_( + &obj->ethertype, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=9216] payload + if (obj->payload.count > 9216) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->payload.count, 16U); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 16U; + for (size_t _index2_ = 0U; _index2_ < obj->payload.count; ++_index2_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->payload.elements[_index2_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_ethernet_Frame_0_1_deserialize_( + uavcan_metatransport_ethernet_Frame_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[6] destination + for (size_t _index3_ = 0U; _index3_ < 6UL; ++_index3_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->destination[_index3_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->destination[_index3_] = 0U; + } + offset_bits += 8U; + } + // saturated uint8[6] source + for (size_t _index4_ = 0U; _index4_ < 6UL; ++_index4_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->source[_index4_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->source[_index4_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.metatransport.ethernet.EtherType.0.1 ethertype + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_metatransport_ethernet_EtherType_0_1_deserialize_( + &out_obj->ethertype, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=9216] payload + // Array length prefix: truncated uint16 + out_obj->payload.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->payload.count > 9216U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index5_ = 0U; _index5_ < out_obj->payload.count; ++_index5_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->payload.elements[_index5_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->payload.elements[_index5_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_ethernet_Frame_0_1_initialize_(uavcan_metatransport_ethernet_Frame_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_ethernet_Frame_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_ETHERNET_FRAME_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_1.h new file mode 100644 index 0000000..bc7852e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_1.h @@ -0,0 +1,277 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.028416 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.serial.Fragment +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_serial_Fragment_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.serial.Fragment.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_serial_Fragment_0_1_FULL_NAME_ "uavcan.metatransport.serial.Fragment" +#define uavcan_metatransport_serial_Fragment_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.serial.Fragment.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_serial_Fragment_0_1_EXTENT_BYTES_ 265UL +#define uavcan_metatransport_serial_Fragment_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 265UL +static_assert(uavcan_metatransport_serial_Fragment_0_1_EXTENT_BYTES_ >= uavcan_metatransport_serial_Fragment_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint9 CAPACITY_BYTES = 256 +#define uavcan_metatransport_serial_Fragment_0_1_CAPACITY_BYTES (256U) + +/// Array metadata for: saturated uint8[<=256] data +#define uavcan_metatransport_serial_Fragment_0_1_data_ARRAY_CAPACITY_ 256U +#define uavcan_metatransport_serial_Fragment_0_1_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated uint8[<=256] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_metatransport_serial_Fragment_0_1_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_metatransport_serial_Fragment_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_serial_Fragment_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_serial_Fragment_0_1_serialize_( + const uavcan_metatransport_serial_Fragment_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2120UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=256] data + if (obj->data.count > 256) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->data.count, 16U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_serial_Fragment_0_1_deserialize_( + uavcan_metatransport_serial_Fragment_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=256] data + // Array length prefix: truncated uint16 + out_obj->data.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->data.count > 256U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_serial_Fragment_0_1_initialize_(uavcan_metatransport_serial_Fragment_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_serial_Fragment_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_2.h b/components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_2.h new file mode 100644 index 0000000..d3e989f --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/serial/Fragment_0_2.h @@ -0,0 +1,242 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.2.dsdl +// Generated at: 2024-09-11 21:29:54.024114 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.serial.Fragment +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_2_INCLUDED_ +#define UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_2_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/serial/Fragment.0.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_serial_Fragment_0_2_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.serial.Fragment.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_serial_Fragment_0_2_FULL_NAME_ "uavcan.metatransport.serial.Fragment" +#define uavcan_metatransport_serial_Fragment_0_2_FULL_NAME_AND_VERSION_ "uavcan.metatransport.serial.Fragment.0.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_serial_Fragment_0_2_EXTENT_BYTES_ 2050UL +#define uavcan_metatransport_serial_Fragment_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 2050UL +static_assert(uavcan_metatransport_serial_Fragment_0_2_EXTENT_BYTES_ >= uavcan_metatransport_serial_Fragment_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint12 CAPACITY_BYTES = 2048 +#define uavcan_metatransport_serial_Fragment_0_2_CAPACITY_BYTES (2048U) + +/// Array metadata for: saturated uint8[<=2048] data +#define uavcan_metatransport_serial_Fragment_0_2_data_ARRAY_CAPACITY_ 2048U +#define uavcan_metatransport_serial_Fragment_0_2_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=2048] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_metatransport_serial_Fragment_0_2_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_metatransport_serial_Fragment_0_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_serial_Fragment_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_serial_Fragment_0_2_serialize_( + const uavcan_metatransport_serial_Fragment_0_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16400UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=2048] data + if (obj->data.count > 2048) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->data.count, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_serial_Fragment_0_2_deserialize_( + uavcan_metatransport_serial_Fragment_0_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=2048] data + // Array length prefix: truncated uint16 + out_obj->data.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->data.count > 2048U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_serial_Fragment_0_2_initialize_(uavcan_metatransport_serial_Fragment_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_serial_Fragment_0_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_2_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/udp/Endpoint_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/udp/Endpoint_0_1.h new file mode 100644 index 0000000..ed9b6f5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/udp/Endpoint_0_1.h @@ -0,0 +1,282 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Endpoint.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.033487 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.udp.Endpoint +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_METATRANSPORT_UDP_ENDPOINT_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_UDP_ENDPOINT_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Endpoint.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Endpoint.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Endpoint.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Endpoint.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Endpoint.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_udp_Endpoint_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.udp.Endpoint.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_udp_Endpoint_0_1_FULL_NAME_ "uavcan.metatransport.udp.Endpoint" +#define uavcan_metatransport_udp_Endpoint_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.udp.Endpoint.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_udp_Endpoint_0_1_EXTENT_BYTES_ 32UL +#define uavcan_metatransport_udp_Endpoint_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 32UL +static_assert(uavcan_metatransport_udp_Endpoint_0_1_EXTENT_BYTES_ >= uavcan_metatransport_udp_Endpoint_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[16] ip_address +#define uavcan_metatransport_udp_Endpoint_0_1_ip_address_ARRAY_CAPACITY_ 16U +#define uavcan_metatransport_udp_Endpoint_0_1_ip_address_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: saturated uint8[6] mac_address +#define uavcan_metatransport_udp_Endpoint_0_1_mac_address_ARRAY_CAPACITY_ 6U +#define uavcan_metatransport_udp_Endpoint_0_1_mac_address_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated uint8[16] ip_address + uint8_t ip_address[16]; + + /// saturated uint8[6] mac_address + uint8_t mac_address[6]; + + /// saturated uint16 port + uint16_t port; +} uavcan_metatransport_udp_Endpoint_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_udp_Endpoint_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_udp_Endpoint_0_1_serialize_( + const uavcan_metatransport_udp_Endpoint_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 256UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[16] ip_address + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->ip_address[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + { // saturated uint8[6] mac_address + const size_t _origin1_ = offset_bits; + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->mac_address[_index1_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin1_; + } + { // saturated uint16 port + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->port, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // void64 + (void) memset(&buffer[offset_bits / 8U], 0, 8); + offset_bits += 64UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_udp_Endpoint_0_1_deserialize_( + uavcan_metatransport_udp_Endpoint_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[16] ip_address + for (size_t _index2_ = 0U; _index2_ < 16UL; ++_index2_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->ip_address[_index2_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->ip_address[_index2_] = 0U; + } + offset_bits += 8U; + } + // saturated uint8[6] mac_address + for (size_t _index3_ = 0U; _index3_ < 6UL; ++_index3_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->mac_address[_index3_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->mac_address[_index3_] = 0U; + } + offset_bits += 8U; + } + // saturated uint16 port + out_obj->port = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // void64 + offset_bits += 64; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_udp_Endpoint_0_1_initialize_(uavcan_metatransport_udp_Endpoint_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_udp_Endpoint_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_UDP_ENDPOINT_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/metatransport/udp/Frame_0_1.h b/components/esp_nunavut/nunavut/uavcan/metatransport/udp/Frame_0_1.h new file mode 100644 index 0000000..6bafb2a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/metatransport/udp/Frame_0_1.h @@ -0,0 +1,357 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Frame.0.1.dsdl +// Generated at: 2024-09-11 21:29:54.041524 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.udp.Frame +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_METATRANSPORT_UDP_FRAME_0_1_INCLUDED_ +#define UAVCAN_METATRANSPORT_UDP_FRAME_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/metatransport/udp/Frame.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_metatransport_udp_Frame_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.metatransport.udp.Frame.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_metatransport_udp_Frame_0_1_FULL_NAME_ "uavcan.metatransport.udp.Frame" +#define uavcan_metatransport_udp_Frame_0_1_FULL_NAME_AND_VERSION_ "uavcan.metatransport.udp.Frame.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_metatransport_udp_Frame_0_1_EXTENT_BYTES_ 10240UL +#define uavcan_metatransport_udp_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 9262UL +static_assert(uavcan_metatransport_udp_Frame_0_1_EXTENT_BYTES_ >= uavcan_metatransport_udp_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint14 MTU = 9188 +#define uavcan_metatransport_udp_Frame_0_1_MTU (9188U) + +/// Array metadata for: saturated uint8[<=9188] data +#define uavcan_metatransport_udp_Frame_0_1_data_ARRAY_CAPACITY_ 9188U +#define uavcan_metatransport_udp_Frame_0_1_data_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// uavcan.metatransport.udp.Endpoint.0.1 source + uavcan_metatransport_udp_Endpoint_0_1 source; + + /// uavcan.metatransport.udp.Endpoint.0.1 destination + uavcan_metatransport_udp_Endpoint_0_1 destination; + + /// saturated uint8[<=9188] data + struct /// Array address equivalence guarantee: &elements[0] == &data + { + uint8_t elements[uavcan_metatransport_udp_Frame_0_1_data_ARRAY_CAPACITY_]; + size_t count; + } data; +} uavcan_metatransport_udp_Frame_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_metatransport_udp_Frame_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_udp_Frame_0_1_serialize_( + const uavcan_metatransport_udp_Frame_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 74096UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // void8 + buffer[offset_bits / 8U] = 0U; + offset_bits += 8UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.metatransport.udp.Endpoint.0.1 source + size_t _size_bytes1_ = 32UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_metatransport_udp_Endpoint_0_1_serialize_( + &obj->source, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.metatransport.udp.Endpoint.0.1 destination + size_t _size_bytes2_ = 32UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_metatransport_udp_Endpoint_0_1_serialize_( + &obj->destination, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[<=9188] data + if (obj->data.count > 9188) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->data.count, 16U); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->data.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_metatransport_udp_Frame_0_1_deserialize_( + uavcan_metatransport_udp_Frame_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // void8 + offset_bits += 8; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.metatransport.udp.Endpoint.0.1 source + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_metatransport_udp_Endpoint_0_1_deserialize_( + &out_obj->source, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.metatransport.udp.Endpoint.0.1 destination + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err9_ = uavcan_metatransport_udp_Endpoint_0_1_deserialize_( + &out_obj->destination, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[<=9188] data + // Array length prefix: truncated uint16 + out_obj->data.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->data.count > 9188U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->data.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->data.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_metatransport_udp_Frame_0_1_initialize_(uavcan_metatransport_udp_Frame_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_metatransport_udp_Frame_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_UDP_FRAME_0_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_0.h new file mode 100644 index 0000000..836da6e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_0.h @@ -0,0 +1,450 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.409193 UTC +// Is deprecated: yes +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_NODE_EXECUTE_COMMAND_1_0_INCLUDED_ +#define UAVCAN_NODE_EXECUTE_COMMAND_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_ExecuteCommand_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_node_ExecuteCommand_1_0_FIXED_PORT_ID_ 435U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_1_0_FULL_NAME_ "uavcan.node.ExecuteCommand" +#define uavcan_node_ExecuteCommand_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Request_1_0_FULL_NAME_ "uavcan.node.ExecuteCommand.Request" +#define uavcan_node_ExecuteCommand_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Request_1_0_EXTENT_BYTES_ 300UL +#define uavcan_node_ExecuteCommand_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 115UL +static_assert(uavcan_node_ExecuteCommand_Request_1_0_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 COMMAND_RESTART = 65535 +#define uavcan_node_ExecuteCommand_Request_1_0_COMMAND_RESTART (65535U) + +/// saturated uint16 COMMAND_POWER_OFF = 65534 +#define uavcan_node_ExecuteCommand_Request_1_0_COMMAND_POWER_OFF (65534U) + +/// saturated uint16 COMMAND_BEGIN_SOFTWARE_UPDATE = 65533 +#define uavcan_node_ExecuteCommand_Request_1_0_COMMAND_BEGIN_SOFTWARE_UPDATE (65533U) + +/// saturated uint16 COMMAND_FACTORY_RESET = 65532 +#define uavcan_node_ExecuteCommand_Request_1_0_COMMAND_FACTORY_RESET (65532U) + +/// saturated uint16 COMMAND_EMERGENCY_STOP = 65531 +#define uavcan_node_ExecuteCommand_Request_1_0_COMMAND_EMERGENCY_STOP (65531U) + +/// saturated uint16 COMMAND_STORE_PERSISTENT_STATES = 65530 +#define uavcan_node_ExecuteCommand_Request_1_0_COMMAND_STORE_PERSISTENT_STATES (65530U) + +/// Array metadata for: saturated uint8[<=112] parameter +#define uavcan_node_ExecuteCommand_Request_1_0_parameter_ARRAY_CAPACITY_ 112U +#define uavcan_node_ExecuteCommand_Request_1_0_parameter_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 command + uint16_t command; + + /// saturated uint8[<=112] parameter + struct /// Array address equivalence guarantee: &elements[0] == ¶meter + { + uint8_t elements[uavcan_node_ExecuteCommand_Request_1_0_parameter_ARRAY_CAPACITY_]; + size_t count; + } parameter; +} uavcan_node_ExecuteCommand_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_0_serialize_( + const uavcan_node_ExecuteCommand_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 920UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 command + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->command, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint8[<=112] parameter + if (obj->parameter.count > 112) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_0_deserialize_( + uavcan_node_ExecuteCommand_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 command + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=112] parameter + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.count = 0U; + } + offset_bits += 8U; + if (out_obj->parameter.count > 112U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Request_1_0_initialize_(uavcan_node_ExecuteCommand_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Response_1_0_FULL_NAME_ "uavcan.node.ExecuteCommand.Response" +#define uavcan_node_ExecuteCommand_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Response_1_0_EXTENT_BYTES_ 48UL +#define uavcan_node_ExecuteCommand_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_node_ExecuteCommand_Response_1_0_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 STATUS_SUCCESS = 0 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_SUCCESS (0U) + +/// saturated uint8 STATUS_FAILURE = 1 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_FAILURE (1U) + +/// saturated uint8 STATUS_NOT_AUTHORIZED = 2 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_NOT_AUTHORIZED (2U) + +/// saturated uint8 STATUS_BAD_COMMAND = 3 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_BAD_COMMAND (3U) + +/// saturated uint8 STATUS_BAD_PARAMETER = 4 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_BAD_PARAMETER (4U) + +/// saturated uint8 STATUS_BAD_STATE = 5 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_BAD_STATE (5U) + +/// saturated uint8 STATUS_INTERNAL_ERROR = 6 +#define uavcan_node_ExecuteCommand_Response_1_0_STATUS_INTERNAL_ERROR (6U) + +typedef struct +{ + /// saturated uint8 status + uint8_t status; +} uavcan_node_ExecuteCommand_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_0_serialize_( + const uavcan_node_ExecuteCommand_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8 status + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->status); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_0_deserialize_( + uavcan_node_ExecuteCommand_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8 status + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->status = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->status = 0U; + } + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Response_1_0_initialize_(uavcan_node_ExecuteCommand_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_1.h b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_1.h new file mode 100644 index 0000000..7bc9586 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_1.h @@ -0,0 +1,450 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.402060 UTC +// Is deprecated: yes +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_NODE_EXECUTE_COMMAND_1_1_INCLUDED_ +#define UAVCAN_NODE_EXECUTE_COMMAND_1_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_ExecuteCommand_1_1_HAS_FIXED_PORT_ID_ true +#define uavcan_node_ExecuteCommand_1_1_FIXED_PORT_ID_ 435U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_1_1_FULL_NAME_ "uavcan.node.ExecuteCommand" +#define uavcan_node_ExecuteCommand_1_1_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.1.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Request.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Request_1_1_FULL_NAME_ "uavcan.node.ExecuteCommand.Request" +#define uavcan_node_ExecuteCommand_Request_1_1_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Request.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Request_1_1_EXTENT_BYTES_ 300UL +#define uavcan_node_ExecuteCommand_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_node_ExecuteCommand_Request_1_1_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 COMMAND_RESTART = 65535 +#define uavcan_node_ExecuteCommand_Request_1_1_COMMAND_RESTART (65535U) + +/// saturated uint16 COMMAND_POWER_OFF = 65534 +#define uavcan_node_ExecuteCommand_Request_1_1_COMMAND_POWER_OFF (65534U) + +/// saturated uint16 COMMAND_BEGIN_SOFTWARE_UPDATE = 65533 +#define uavcan_node_ExecuteCommand_Request_1_1_COMMAND_BEGIN_SOFTWARE_UPDATE (65533U) + +/// saturated uint16 COMMAND_FACTORY_RESET = 65532 +#define uavcan_node_ExecuteCommand_Request_1_1_COMMAND_FACTORY_RESET (65532U) + +/// saturated uint16 COMMAND_EMERGENCY_STOP = 65531 +#define uavcan_node_ExecuteCommand_Request_1_1_COMMAND_EMERGENCY_STOP (65531U) + +/// saturated uint16 COMMAND_STORE_PERSISTENT_STATES = 65530 +#define uavcan_node_ExecuteCommand_Request_1_1_COMMAND_STORE_PERSISTENT_STATES (65530U) + +/// Array metadata for: saturated uint8[<=255] parameter +#define uavcan_node_ExecuteCommand_Request_1_1_parameter_ARRAY_CAPACITY_ 255U +#define uavcan_node_ExecuteCommand_Request_1_1_parameter_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 command + uint16_t command; + + /// saturated uint8[<=255] parameter + struct /// Array address equivalence guarantee: &elements[0] == ¶meter + { + uint8_t elements[uavcan_node_ExecuteCommand_Request_1_1_parameter_ARRAY_CAPACITY_]; + size_t count; + } parameter; +} uavcan_node_ExecuteCommand_Request_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Request_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_1_serialize_( + const uavcan_node_ExecuteCommand_Request_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 command + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->command, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint8[<=255] parameter + if (obj->parameter.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_1_deserialize_( + uavcan_node_ExecuteCommand_Request_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 command + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=255] parameter + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.count = 0U; + } + offset_bits += 8U; + if (out_obj->parameter.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Request_1_1_initialize_(uavcan_node_ExecuteCommand_Request_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Request_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Response.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Response_1_1_FULL_NAME_ "uavcan.node.ExecuteCommand.Response" +#define uavcan_node_ExecuteCommand_Response_1_1_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Response.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Response_1_1_EXTENT_BYTES_ 48UL +#define uavcan_node_ExecuteCommand_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_node_ExecuteCommand_Response_1_1_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 STATUS_SUCCESS = 0 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_SUCCESS (0U) + +/// saturated uint8 STATUS_FAILURE = 1 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_FAILURE (1U) + +/// saturated uint8 STATUS_NOT_AUTHORIZED = 2 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_NOT_AUTHORIZED (2U) + +/// saturated uint8 STATUS_BAD_COMMAND = 3 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_BAD_COMMAND (3U) + +/// saturated uint8 STATUS_BAD_PARAMETER = 4 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_BAD_PARAMETER (4U) + +/// saturated uint8 STATUS_BAD_STATE = 5 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_BAD_STATE (5U) + +/// saturated uint8 STATUS_INTERNAL_ERROR = 6 +#define uavcan_node_ExecuteCommand_Response_1_1_STATUS_INTERNAL_ERROR (6U) + +typedef struct +{ + /// saturated uint8 status + uint8_t status; +} uavcan_node_ExecuteCommand_Response_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_1_serialize_( + const uavcan_node_ExecuteCommand_Response_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8 status + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->status); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_1_deserialize_( + uavcan_node_ExecuteCommand_Response_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8 status + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->status = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->status = 0U; + } + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Response_1_1_initialize_(uavcan_node_ExecuteCommand_Response_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Response_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_2.h b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_2.h new file mode 100644 index 0000000..6e2ed73 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_2.h @@ -0,0 +1,453 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.2.dsdl +// Generated at: 2024-09-11 21:29:53.394844 UTC +// Is deprecated: yes +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_NODE_EXECUTE_COMMAND_1_2_INCLUDED_ +#define UAVCAN_NODE_EXECUTE_COMMAND_1_2_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.2.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_ExecuteCommand_1_2_HAS_FIXED_PORT_ID_ true +#define uavcan_node_ExecuteCommand_1_2_FIXED_PORT_ID_ 435U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.1.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_1_2_FULL_NAME_ "uavcan.node.ExecuteCommand" +#define uavcan_node_ExecuteCommand_1_2_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.1.2" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Request.1.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Request_1_2_FULL_NAME_ "uavcan.node.ExecuteCommand.Request" +#define uavcan_node_ExecuteCommand_Request_1_2_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Request.1.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Request_1_2_EXTENT_BYTES_ 300UL +#define uavcan_node_ExecuteCommand_Request_1_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_node_ExecuteCommand_Request_1_2_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Request_1_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 COMMAND_RESTART = 65535 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_RESTART (65535U) + +/// saturated uint16 COMMAND_POWER_OFF = 65534 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_POWER_OFF (65534U) + +/// saturated uint16 COMMAND_BEGIN_SOFTWARE_UPDATE = 65533 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_BEGIN_SOFTWARE_UPDATE (65533U) + +/// saturated uint16 COMMAND_FACTORY_RESET = 65532 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_FACTORY_RESET (65532U) + +/// saturated uint16 COMMAND_EMERGENCY_STOP = 65531 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_EMERGENCY_STOP (65531U) + +/// saturated uint16 COMMAND_STORE_PERSISTENT_STATES = 65530 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_STORE_PERSISTENT_STATES (65530U) + +/// saturated uint16 COMMAND_IDENTIFY = 65529 +#define uavcan_node_ExecuteCommand_Request_1_2_COMMAND_IDENTIFY (65529U) + +/// Array metadata for: saturated uint8[<=255] parameter +#define uavcan_node_ExecuteCommand_Request_1_2_parameter_ARRAY_CAPACITY_ 255U +#define uavcan_node_ExecuteCommand_Request_1_2_parameter_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 command + uint16_t command; + + /// saturated uint8[<=255] parameter + struct /// Array address equivalence guarantee: &elements[0] == ¶meter + { + uint8_t elements[uavcan_node_ExecuteCommand_Request_1_2_parameter_ARRAY_CAPACITY_]; + size_t count; + } parameter; +} uavcan_node_ExecuteCommand_Request_1_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Request_1_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_2_serialize_( + const uavcan_node_ExecuteCommand_Request_1_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 command + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->command, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint8[<=255] parameter + if (obj->parameter.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_2_deserialize_( + uavcan_node_ExecuteCommand_Request_1_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 command + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=255] parameter + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.count = 0U; + } + offset_bits += 8U; + if (out_obj->parameter.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Request_1_2_initialize_(uavcan_node_ExecuteCommand_Request_1_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Request_1_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Response.1.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Response_1_2_FULL_NAME_ "uavcan.node.ExecuteCommand.Response" +#define uavcan_node_ExecuteCommand_Response_1_2_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Response.1.2" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Response_1_2_EXTENT_BYTES_ 48UL +#define uavcan_node_ExecuteCommand_Response_1_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_node_ExecuteCommand_Response_1_2_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Response_1_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 STATUS_SUCCESS = 0 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_SUCCESS (0U) + +/// saturated uint8 STATUS_FAILURE = 1 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_FAILURE (1U) + +/// saturated uint8 STATUS_NOT_AUTHORIZED = 2 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_NOT_AUTHORIZED (2U) + +/// saturated uint8 STATUS_BAD_COMMAND = 3 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_BAD_COMMAND (3U) + +/// saturated uint8 STATUS_BAD_PARAMETER = 4 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_BAD_PARAMETER (4U) + +/// saturated uint8 STATUS_BAD_STATE = 5 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_BAD_STATE (5U) + +/// saturated uint8 STATUS_INTERNAL_ERROR = 6 +#define uavcan_node_ExecuteCommand_Response_1_2_STATUS_INTERNAL_ERROR (6U) + +typedef struct +{ + /// saturated uint8 status + uint8_t status; +} uavcan_node_ExecuteCommand_Response_1_2; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Response_1_2_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_2_serialize_( + const uavcan_node_ExecuteCommand_Response_1_2* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8 status + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->status); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_2_deserialize_( + uavcan_node_ExecuteCommand_Response_1_2* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8 status + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->status = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->status = 0U; + } + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Response_1_2_initialize_(uavcan_node_ExecuteCommand_Response_1_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Response_1_2_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_2_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_3.h b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_3.h new file mode 100644 index 0000000..9276dbd --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/ExecuteCommand_1_3.h @@ -0,0 +1,497 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.3.dsdl +// Generated at: 2024-09-11 21:29:53.385888 UTC +// Is deprecated: no +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.3 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_EXECUTE_COMMAND_1_3_INCLUDED_ +#define UAVCAN_NODE_EXECUTE_COMMAND_1_3_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.3.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.3.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.3.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.3.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/435.ExecuteCommand.1.3.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_ExecuteCommand_1_3_HAS_FIXED_PORT_ID_ true +#define uavcan_node_ExecuteCommand_1_3_FIXED_PORT_ID_ 435U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.1.3 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_1_3_FULL_NAME_ "uavcan.node.ExecuteCommand" +#define uavcan_node_ExecuteCommand_1_3_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.1.3" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Request.1.3 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Request_1_3_FULL_NAME_ "uavcan.node.ExecuteCommand.Request" +#define uavcan_node_ExecuteCommand_Request_1_3_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Request.1.3" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Request_1_3_EXTENT_BYTES_ 300UL +#define uavcan_node_ExecuteCommand_Request_1_3_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_node_ExecuteCommand_Request_1_3_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Request_1_3_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 COMMAND_RESTART = 65535 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_RESTART (65535U) + +/// saturated uint16 COMMAND_POWER_OFF = 65534 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_POWER_OFF (65534U) + +/// saturated uint16 COMMAND_BEGIN_SOFTWARE_UPDATE = 65533 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_BEGIN_SOFTWARE_UPDATE (65533U) + +/// saturated uint16 COMMAND_FACTORY_RESET = 65532 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_FACTORY_RESET (65532U) + +/// saturated uint16 COMMAND_EMERGENCY_STOP = 65531 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_EMERGENCY_STOP (65531U) + +/// saturated uint16 COMMAND_STORE_PERSISTENT_STATES = 65530 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_STORE_PERSISTENT_STATES (65530U) + +/// saturated uint16 COMMAND_IDENTIFY = 65529 +#define uavcan_node_ExecuteCommand_Request_1_3_COMMAND_IDENTIFY (65529U) + +/// Array metadata for: saturated uint8[<=255] parameter +#define uavcan_node_ExecuteCommand_Request_1_3_parameter_ARRAY_CAPACITY_ 255U +#define uavcan_node_ExecuteCommand_Request_1_3_parameter_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16 command + uint16_t command; + + /// saturated uint8[<=255] parameter + struct /// Array address equivalence guarantee: &elements[0] == ¶meter + { + uint8_t elements[uavcan_node_ExecuteCommand_Request_1_3_parameter_ARRAY_CAPACITY_]; + size_t count; + } parameter; +} uavcan_node_ExecuteCommand_Request_1_3; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Request_1_3_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_3_serialize_( + const uavcan_node_ExecuteCommand_Request_1_3* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 command + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->command, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + { // saturated uint8[<=255] parameter + if (obj->parameter.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->parameter.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Request_1_3_deserialize_( + uavcan_node_ExecuteCommand_Request_1_3* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 command + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=255] parameter + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.count = 0U; + } + offset_bits += 8U; + if (out_obj->parameter.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->parameter.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->parameter.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Request_1_3_initialize_(uavcan_node_ExecuteCommand_Request_1_3* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Request_1_3_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ExecuteCommand.Response.1.3 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ExecuteCommand_Response_1_3_FULL_NAME_ "uavcan.node.ExecuteCommand.Response" +#define uavcan_node_ExecuteCommand_Response_1_3_FULL_NAME_AND_VERSION_ "uavcan.node.ExecuteCommand.Response.1.3" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ExecuteCommand_Response_1_3_EXTENT_BYTES_ 48UL +#define uavcan_node_ExecuteCommand_Response_1_3_SERIALIZATION_BUFFER_SIZE_BYTES_ 48UL +static_assert(uavcan_node_ExecuteCommand_Response_1_3_EXTENT_BYTES_ >= uavcan_node_ExecuteCommand_Response_1_3_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 STATUS_SUCCESS = 0 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_SUCCESS (0U) + +/// saturated uint8 STATUS_FAILURE = 1 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_FAILURE (1U) + +/// saturated uint8 STATUS_NOT_AUTHORIZED = 2 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_NOT_AUTHORIZED (2U) + +/// saturated uint8 STATUS_BAD_COMMAND = 3 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_BAD_COMMAND (3U) + +/// saturated uint8 STATUS_BAD_PARAMETER = 4 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_BAD_PARAMETER (4U) + +/// saturated uint8 STATUS_BAD_STATE = 5 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_BAD_STATE (5U) + +/// saturated uint8 STATUS_INTERNAL_ERROR = 6 +#define uavcan_node_ExecuteCommand_Response_1_3_STATUS_INTERNAL_ERROR (6U) + +/// Array metadata for: saturated uint8[<=46] output +#define uavcan_node_ExecuteCommand_Response_1_3_output_ARRAY_CAPACITY_ 46U +#define uavcan_node_ExecuteCommand_Response_1_3_output_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8 status + uint8_t status; + + /// saturated uint8[<=46] output + struct /// Array address equivalence guarantee: &elements[0] == &output + { + uint8_t elements[uavcan_node_ExecuteCommand_Response_1_3_output_ARRAY_CAPACITY_]; + size_t count; + } output; +} uavcan_node_ExecuteCommand_Response_1_3; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ExecuteCommand_Response_1_3_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_3_serialize_( + const uavcan_node_ExecuteCommand_Response_1_3* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 384UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8 status + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->status); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + { // saturated uint8[<=46] output + if (obj->output.count > 46) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->output.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index2_ = 0U; _index2_ < obj->output.count; ++_index2_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->output.elements[_index2_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ExecuteCommand_Response_1_3_deserialize_( + uavcan_node_ExecuteCommand_Response_1_3* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8 status + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->status = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->status = 0U; + } + offset_bits += 8U; + // saturated uint8[<=46] output + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->output.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->output.count = 0U; + } + offset_bits += 8U; + if (out_obj->output.count > 46U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index3_ = 0U; _index3_ < out_obj->output.count; ++_index3_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->output.elements[_index3_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->output.elements[_index3_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ExecuteCommand_Response_1_3_initialize_(uavcan_node_ExecuteCommand_Response_1_3* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ExecuteCommand_Response_1_3_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_3_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/GetInfo_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/GetInfo_1_0.h new file mode 100644 index 0000000..c056b2b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/GetInfo_1_0.h @@ -0,0 +1,596 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/430.GetInfo.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.416245 UTC +// Is deprecated: no +// Fixed port-ID: 430 +// Full name: uavcan.node.GetInfo +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_GET_INFO_1_0_INCLUDED_ +#define UAVCAN_NODE_GET_INFO_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/430.GetInfo.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/430.GetInfo.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/430.GetInfo.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/430.GetInfo.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/430.GetInfo.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_GetInfo_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_node_GetInfo_1_0_FIXED_PORT_ID_ 430U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.GetInfo.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_GetInfo_1_0_FULL_NAME_ "uavcan.node.GetInfo" +#define uavcan_node_GetInfo_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.GetInfo.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.GetInfo.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_GetInfo_Request_1_0_FULL_NAME_ "uavcan.node.GetInfo.Request" +#define uavcan_node_GetInfo_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.GetInfo.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_GetInfo_Request_1_0_EXTENT_BYTES_ 0UL +#define uavcan_node_GetInfo_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(uavcan_node_GetInfo_Request_1_0_EXTENT_BYTES_ >= uavcan_node_GetInfo_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_node_GetInfo_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_GetInfo_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetInfo_Request_1_0_serialize_( + const uavcan_node_GetInfo_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetInfo_Request_1_0_deserialize_( + uavcan_node_GetInfo_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_GetInfo_Request_1_0_initialize_(uavcan_node_GetInfo_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_GetInfo_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.GetInfo.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_GetInfo_Response_1_0_FULL_NAME_ "uavcan.node.GetInfo.Response" +#define uavcan_node_GetInfo_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.GetInfo.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_GetInfo_Response_1_0_EXTENT_BYTES_ 448UL +#define uavcan_node_GetInfo_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 313UL +static_assert(uavcan_node_GetInfo_Response_1_0_EXTENT_BYTES_ >= uavcan_node_GetInfo_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[16] unique_id +#define uavcan_node_GetInfo_Response_1_0_unique_id_ARRAY_CAPACITY_ 16U +#define uavcan_node_GetInfo_Response_1_0_unique_id_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: saturated uint8[<=50] name +#define uavcan_node_GetInfo_Response_1_0_name_ARRAY_CAPACITY_ 50U +#define uavcan_node_GetInfo_Response_1_0_name_ARRAY_IS_VARIABLE_LENGTH_ true + +/// Array metadata for: saturated uint64[<=1] software_image_crc +#define uavcan_node_GetInfo_Response_1_0_software_image_crc_ARRAY_CAPACITY_ 1U +#define uavcan_node_GetInfo_Response_1_0_software_image_crc_ARRAY_IS_VARIABLE_LENGTH_ true + +/// Array metadata for: saturated uint8[<=222] certificate_of_authenticity +#define uavcan_node_GetInfo_Response_1_0_certificate_of_authenticity_ARRAY_CAPACITY_ 222U +#define uavcan_node_GetInfo_Response_1_0_certificate_of_authenticity_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.node.Version.1.0 protocol_version + uavcan_node_Version_1_0 protocol_version; + + /// uavcan.node.Version.1.0 hardware_version + uavcan_node_Version_1_0 hardware_version; + + /// uavcan.node.Version.1.0 software_version + uavcan_node_Version_1_0 software_version; + + /// saturated uint64 software_vcs_revision_id + uint64_t software_vcs_revision_id; + + /// saturated uint8[16] unique_id + uint8_t unique_id[16]; + + /// saturated uint8[<=50] name + struct /// Array address equivalence guarantee: &elements[0] == &name + { + uint8_t elements[uavcan_node_GetInfo_Response_1_0_name_ARRAY_CAPACITY_]; + size_t count; + } name; + + /// saturated uint64[<=1] software_image_crc + struct /// Array address equivalence guarantee: &elements[0] == &software_image_crc + { + uint64_t elements[uavcan_node_GetInfo_Response_1_0_software_image_crc_ARRAY_CAPACITY_]; + size_t count; + } software_image_crc; + + /// saturated uint8[<=222] certificate_of_authenticity + struct /// Array address equivalence guarantee: &elements[0] == &certificate_of_authenticity + { + uint8_t elements[uavcan_node_GetInfo_Response_1_0_certificate_of_authenticity_ARRAY_CAPACITY_]; + size_t count; + } certificate_of_authenticity; +} uavcan_node_GetInfo_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_GetInfo_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetInfo_Response_1_0_serialize_( + const uavcan_node_GetInfo_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2504UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.node.Version.1.0 protocol_version + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_node_Version_1_0_serialize_( + &obj->protocol_version, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.Version.1.0 hardware_version + size_t _size_bytes1_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_node_Version_1_0_serialize_( + &obj->hardware_version, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.node.Version.1.0 software_version + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_node_Version_1_0_serialize_( + &obj->software_version, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint64 software_vcs_revision_id + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->software_vcs_revision_id, 64U); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 64U; + } + { // saturated uint8[16] unique_id + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->unique_id[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + { // saturated uint8[<=50] name + if (obj->name.count > 50) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->name.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index1_ = 0U; _index1_ < obj->name.count; ++_index1_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->name.elements[_index1_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + { // saturated uint64[<=1] software_image_crc + if (obj->software_image_crc.count > 1) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->software_image_crc.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index2_ = 0U; _index2_ < obj->software_image_crc.count; ++_index2_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->software_image_crc.elements[_index2_], 64U); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += 64U; + } + } + { // saturated uint8[<=222] certificate_of_authenticity + if (obj->certificate_of_authenticity.count > 222) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->certificate_of_authenticity.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index3_ = 0U; _index3_ < obj->certificate_of_authenticity.count; ++_index3_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->certificate_of_authenticity.elements[_index3_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetInfo_Response_1_0_deserialize_( + uavcan_node_GetInfo_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.node.Version.1.0 protocol_version + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err8_ = uavcan_node_Version_1_0_deserialize_( + &out_obj->protocol_version, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.Version.1.0 hardware_version + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err9_ = uavcan_node_Version_1_0_deserialize_( + &out_obj->hardware_version, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.Version.1.0 software_version + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err10_ = uavcan_node_Version_1_0_deserialize_( + &out_obj->software_version, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint64 software_vcs_revision_id + out_obj->software_vcs_revision_id = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + // saturated uint8[16] unique_id + for (size_t _index4_ = 0U; _index4_ < 16UL; ++_index4_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->unique_id[_index4_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->unique_id[_index4_] = 0U; + } + offset_bits += 8U; + } + // saturated uint8[<=50] name + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->name.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->name.count = 0U; + } + offset_bits += 8U; + if (out_obj->name.count > 50U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index5_ = 0U; _index5_ < out_obj->name.count; ++_index5_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->name.elements[_index5_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->name.elements[_index5_] = 0U; + } + offset_bits += 8U; + } + // saturated uint64[<=1] software_image_crc + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->software_image_crc.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->software_image_crc.count = 0U; + } + offset_bits += 8U; + if (out_obj->software_image_crc.count > 1U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index6_ = 0U; _index6_ < out_obj->software_image_crc.count; ++_index6_) + { + out_obj->software_image_crc.elements[_index6_] = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + } + // saturated uint8[<=222] certificate_of_authenticity + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->certificate_of_authenticity.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->certificate_of_authenticity.count = 0U; + } + offset_bits += 8U; + if (out_obj->certificate_of_authenticity.count > 222U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index7_ = 0U; _index7_ < out_obj->certificate_of_authenticity.count; ++_index7_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->certificate_of_authenticity.elements[_index7_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->certificate_of_authenticity.elements[_index7_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_GetInfo_Response_1_0_initialize_(uavcan_node_GetInfo_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_GetInfo_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_GET_INFO_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/GetTransportStatistics_0_1.h b/components/esp_nunavut/nunavut/uavcan/node/GetTransportStatistics_0_1.h new file mode 100644 index 0000000..0f936d5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/GetTransportStatistics_0_1.h @@ -0,0 +1,395 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/434.GetTransportStatistics.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.427429 UTC +// Is deprecated: no +// Fixed port-ID: 434 +// Full name: uavcan.node.GetTransportStatistics +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_GET_TRANSPORT_STATISTICS_0_1_INCLUDED_ +#define UAVCAN_NODE_GET_TRANSPORT_STATISTICS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/434.GetTransportStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/434.GetTransportStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/434.GetTransportStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/434.GetTransportStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/434.GetTransportStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_GetTransportStatistics_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_node_GetTransportStatistics_0_1_FIXED_PORT_ID_ 434U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.GetTransportStatistics.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_GetTransportStatistics_0_1_FULL_NAME_ "uavcan.node.GetTransportStatistics" +#define uavcan_node_GetTransportStatistics_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.GetTransportStatistics.0.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.GetTransportStatistics.Request.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_GetTransportStatistics_Request_0_1_FULL_NAME_ "uavcan.node.GetTransportStatistics.Request" +#define uavcan_node_GetTransportStatistics_Request_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.GetTransportStatistics.Request.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_GetTransportStatistics_Request_0_1_EXTENT_BYTES_ 0UL +#define uavcan_node_GetTransportStatistics_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(uavcan_node_GetTransportStatistics_Request_0_1_EXTENT_BYTES_ >= uavcan_node_GetTransportStatistics_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_node_GetTransportStatistics_Request_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_GetTransportStatistics_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetTransportStatistics_Request_0_1_serialize_( + const uavcan_node_GetTransportStatistics_Request_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetTransportStatistics_Request_0_1_deserialize_( + uavcan_node_GetTransportStatistics_Request_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_GetTransportStatistics_Request_0_1_initialize_(uavcan_node_GetTransportStatistics_Request_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_GetTransportStatistics_Request_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.GetTransportStatistics.Response.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_GetTransportStatistics_Response_0_1_FULL_NAME_ "uavcan.node.GetTransportStatistics.Response" +#define uavcan_node_GetTransportStatistics_Response_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.GetTransportStatistics.Response.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_GetTransportStatistics_Response_0_1_EXTENT_BYTES_ 192UL +#define uavcan_node_GetTransportStatistics_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 61UL +static_assert(uavcan_node_GetTransportStatistics_Response_0_1_EXTENT_BYTES_ >= uavcan_node_GetTransportStatistics_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_NETWORK_INTERFACES = 3 +#define uavcan_node_GetTransportStatistics_Response_0_1_MAX_NETWORK_INTERFACES (3U) + +/// Array metadata for: uavcan.node.IOStatistics.0.1[<=3] network_interface_statistics +#define uavcan_node_GetTransportStatistics_Response_0_1_network_interface_statistics_ARRAY_CAPACITY_ 3U +#define uavcan_node_GetTransportStatistics_Response_0_1_network_interface_statistics_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// uavcan.node.IOStatistics.0.1 transfer_statistics + uavcan_node_IOStatistics_0_1 transfer_statistics; + + /// uavcan.node.IOStatistics.0.1[<=3] network_interface_statistics + struct /// Array address equivalence guarantee: &elements[0] == &network_interface_statistics + { + uavcan_node_IOStatistics_0_1 elements[uavcan_node_GetTransportStatistics_Response_0_1_network_interface_statistics_ARRAY_CAPACITY_]; + size_t count; + } network_interface_statistics; +} uavcan_node_GetTransportStatistics_Response_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_GetTransportStatistics_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetTransportStatistics_Response_0_1_serialize_( + const uavcan_node_GetTransportStatistics_Response_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 488UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.node.IOStatistics.0.1 transfer_statistics + size_t _size_bytes0_ = 15UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_node_IOStatistics_0_1_serialize_( + &obj->transfer_statistics, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.IOStatistics.0.1[<=3] network_interface_statistics + if (obj->network_interface_statistics.count > 3) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->network_interface_statistics.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->network_interface_statistics.count; ++_index0_) + { + size_t _size_bytes1_ = 15UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_node_IOStatistics_0_1_serialize_( + &obj->network_interface_statistics.elements[_index0_], &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_GetTransportStatistics_Response_0_1_deserialize_( + uavcan_node_GetTransportStatistics_Response_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.node.IOStatistics.0.1 transfer_statistics + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_node_IOStatistics_0_1_deserialize_( + &out_obj->transfer_statistics, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.IOStatistics.0.1[<=3] network_interface_statistics + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->network_interface_statistics.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->network_interface_statistics.count = 0U; + } + offset_bits += 8U; + if (out_obj->network_interface_statistics.count > 3U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->network_interface_statistics.count; ++_index1_) + { + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err5_ = uavcan_node_IOStatistics_0_1_deserialize_( + &out_obj->network_interface_statistics.elements[_index1_], &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_GetTransportStatistics_Response_0_1_initialize_(uavcan_node_GetTransportStatistics_Response_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_GetTransportStatistics_Response_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_GET_TRANSPORT_STATISTICS_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/Health_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/Health_1_0.h new file mode 100644 index 0000000..9d7cb1e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/Health_1_0.h @@ -0,0 +1,223 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Health.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.434033 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.Health +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_HEALTH_1_0_INCLUDED_ +#define UAVCAN_NODE_HEALTH_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Health.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Health.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Health.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Health.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Health.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_Health_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.Health.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_Health_1_0_FULL_NAME_ "uavcan.node.Health" +#define uavcan_node_Health_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.Health.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_Health_1_0_EXTENT_BYTES_ 1UL +#define uavcan_node_Health_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_node_Health_1_0_EXTENT_BYTES_ >= uavcan_node_Health_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint2 NOMINAL = 0 +#define uavcan_node_Health_1_0_NOMINAL (0U) + +/// saturated uint2 ADVISORY = 1 +#define uavcan_node_Health_1_0_ADVISORY (1U) + +/// saturated uint2 CAUTION = 2 +#define uavcan_node_Health_1_0_CAUTION (2U) + +/// saturated uint2 WARNING = 3 +#define uavcan_node_Health_1_0_WARNING (3U) + +typedef struct +{ + /// saturated uint2 value + uint8_t value; +} uavcan_node_Health_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_Health_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Health_1_0_serialize_( + const uavcan_node_Health_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint2 value + uint8_t _sat0_ = obj->value; + if (_sat0_ > 3U) + { + _sat0_ = 3U; + } + buffer[offset_bits / 8U] = (uint8_t)(_sat0_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 2U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Health_1_0_deserialize_( + uavcan_node_Health_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint2 value + if ((offset_bits + 2U) <= capacity_bits) + { + out_obj->value = buffer[offset_bits / 8U] & 3U; + } + else + { + out_obj->value = 0U; + } + offset_bits += 2U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_Health_1_0_initialize_(uavcan_node_Health_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_Health_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_HEALTH_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/Heartbeat_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/Heartbeat_1_0.h new file mode 100644 index 0000000..5e08793 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/Heartbeat_1_0.h @@ -0,0 +1,303 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/7509.Heartbeat.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.437692 UTC +// Is deprecated: no +// Fixed port-ID: 7509 +// Full name: uavcan.node.Heartbeat +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_HEARTBEAT_1_0_INCLUDED_ +#define UAVCAN_NODE_HEARTBEAT_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/7509.Heartbeat.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/7509.Heartbeat.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/7509.Heartbeat.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/7509.Heartbeat.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/7509.Heartbeat.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_Heartbeat_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_ 7509U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.Heartbeat.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_Heartbeat_1_0_FULL_NAME_ "uavcan.node.Heartbeat" +#define uavcan_node_Heartbeat_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.Heartbeat.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_Heartbeat_1_0_EXTENT_BYTES_ 12UL +#define uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 7UL +static_assert(uavcan_node_Heartbeat_1_0_EXTENT_BYTES_ >= uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 MAX_PUBLICATION_PERIOD = 1 +#define uavcan_node_Heartbeat_1_0_MAX_PUBLICATION_PERIOD (1U) + +/// saturated uint16 OFFLINE_TIMEOUT = 3 +#define uavcan_node_Heartbeat_1_0_OFFLINE_TIMEOUT (3U) + +typedef struct +{ + /// saturated uint32 uptime + uint32_t uptime; + + /// uavcan.node.Health.1.0 health + uavcan_node_Health_1_0 health; + + /// uavcan.node.Mode.1.0 mode + uavcan_node_Mode_1_0 mode; + + /// saturated uint8 vendor_specific_status_code + uint8_t vendor_specific_status_code; +} uavcan_node_Heartbeat_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Heartbeat_1_0_serialize_( + const uavcan_node_Heartbeat_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 56UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 uptime + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->uptime, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.Health.1.0 health + size_t _size_bytes0_ = 1UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_node_Health_1_0_serialize_( + &obj->health, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.node.Mode.1.0 mode + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_node_Mode_1_0_serialize_( + &obj->mode, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8 vendor_specific_status_code + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->vendor_specific_status_code); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Heartbeat_1_0_deserialize_( + uavcan_node_Heartbeat_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 uptime + out_obj->uptime = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.Health.1.0 health + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_node_Health_1_0_deserialize_( + &out_obj->health, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.Mode.1.0 mode + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_node_Mode_1_0_deserialize_( + &out_obj->mode, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8 vendor_specific_status_code + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->vendor_specific_status_code = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->vendor_specific_status_code = 0U; + } + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_Heartbeat_1_0_initialize_(uavcan_node_Heartbeat_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_Heartbeat_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_HEARTBEAT_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/ID_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/ID_1_0.h new file mode 100644 index 0000000..ced10ad --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/ID_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/ID.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.443486 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.ID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_ID_1_0_INCLUDED_ +#define UAVCAN_NODE_ID_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_ID_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.ID.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_ID_1_0_FULL_NAME_ "uavcan.node.ID" +#define uavcan_node_ID_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.ID.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_ID_1_0_EXTENT_BYTES_ 2UL +#define uavcan_node_ID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_node_ID_1_0_EXTENT_BYTES_ >= uavcan_node_ID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint16 value + uint16_t value; +} uavcan_node_ID_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_ID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ID_1_0_serialize_( + const uavcan_node_ID_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_ID_1_0_deserialize_( + uavcan_node_ID_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_ID_1_0_initialize_(uavcan_node_ID_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_ID_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_ID_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/IOStatistics_0_1.h b/components/esp_nunavut/nunavut/uavcan/node/IOStatistics_0_1.h new file mode 100644 index 0000000..1c4b35e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/IOStatistics_0_1.h @@ -0,0 +1,231 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/IOStatistics.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.446801 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.IOStatistics +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_IO_STATISTICS_0_1_INCLUDED_ +#define UAVCAN_NODE_IO_STATISTICS_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/IOStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/IOStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/IOStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/IOStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/IOStatistics.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_IOStatistics_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.IOStatistics.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_IOStatistics_0_1_FULL_NAME_ "uavcan.node.IOStatistics" +#define uavcan_node_IOStatistics_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.IOStatistics.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_IOStatistics_0_1_EXTENT_BYTES_ 15UL +#define uavcan_node_IOStatistics_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 15UL +static_assert(uavcan_node_IOStatistics_0_1_EXTENT_BYTES_ >= uavcan_node_IOStatistics_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// truncated uint40 num_emitted + uint64_t num_emitted; + + /// truncated uint40 num_received + uint64_t num_received; + + /// truncated uint40 num_errored + uint64_t num_errored; +} uavcan_node_IOStatistics_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_IOStatistics_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_IOStatistics_0_1_serialize_( + const uavcan_node_IOStatistics_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 120UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint40 num_emitted + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->num_emitted, 40U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 40U; + } + { // truncated uint40 num_received + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->num_received, 40U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 40U; + } + { // truncated uint40 num_errored + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->num_errored, 40U); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 40U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_IOStatistics_0_1_deserialize_( + uavcan_node_IOStatistics_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint40 num_emitted + out_obj->num_emitted = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 num_received + out_obj->num_received = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 num_errored + out_obj->num_errored = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_IOStatistics_0_1_initialize_(uavcan_node_IOStatistics_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_IOStatistics_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_IO_STATISTICS_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/Mode_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/Mode_1_0.h new file mode 100644 index 0000000..ab33c69 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/Mode_1_0.h @@ -0,0 +1,223 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Mode.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.451080 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.Mode +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_MODE_1_0_INCLUDED_ +#define UAVCAN_NODE_MODE_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Mode.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Mode.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Mode.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Mode.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Mode.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_Mode_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.Mode.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_Mode_1_0_FULL_NAME_ "uavcan.node.Mode" +#define uavcan_node_Mode_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.Mode.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_Mode_1_0_EXTENT_BYTES_ 1UL +#define uavcan_node_Mode_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_node_Mode_1_0_EXTENT_BYTES_ >= uavcan_node_Mode_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint3 OPERATIONAL = 0 +#define uavcan_node_Mode_1_0_OPERATIONAL (0U) + +/// saturated uint3 INITIALIZATION = 1 +#define uavcan_node_Mode_1_0_INITIALIZATION (1U) + +/// saturated uint3 MAINTENANCE = 2 +#define uavcan_node_Mode_1_0_MAINTENANCE (2U) + +/// saturated uint3 SOFTWARE_UPDATE = 3 +#define uavcan_node_Mode_1_0_SOFTWARE_UPDATE (3U) + +typedef struct +{ + /// saturated uint3 value + uint8_t value; +} uavcan_node_Mode_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_Mode_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Mode_1_0_serialize_( + const uavcan_node_Mode_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint3 value + uint8_t _sat0_ = obj->value; + if (_sat0_ > 7U) + { + _sat0_ = 7U; + } + buffer[offset_bits / 8U] = (uint8_t)(_sat0_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 3U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Mode_1_0_deserialize_( + uavcan_node_Mode_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint3 value + if ((offset_bits + 3U) <= capacity_bits) + { + out_obj->value = buffer[offset_bits / 8U] & 7U; + } + else + { + out_obj->value = 0U; + } + offset_bits += 3U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_Mode_1_0_initialize_(uavcan_node_Mode_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_Mode_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_MODE_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/Version_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/Version_1_0.h new file mode 100644 index 0000000..92f4240 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/Version_1_0.h @@ -0,0 +1,225 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Version.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.454676 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.Version +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_VERSION_1_0_INCLUDED_ +#define UAVCAN_NODE_VERSION_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Version.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Version.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Version.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Version.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/Version.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_Version_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.Version.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_Version_1_0_FULL_NAME_ "uavcan.node.Version" +#define uavcan_node_Version_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.Version.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_Version_1_0_EXTENT_BYTES_ 2UL +#define uavcan_node_Version_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_node_Version_1_0_EXTENT_BYTES_ >= uavcan_node_Version_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint8 major + uint8_t major; + + /// saturated uint8 minor + uint8_t minor; +} uavcan_node_Version_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_Version_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Version_1_0_serialize_( + const uavcan_node_Version_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8 major + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->major); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + { // saturated uint8 minor + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->minor); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_Version_1_0_deserialize_( + uavcan_node_Version_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8 major + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->major = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->major = 0U; + } + offset_bits += 8U; + // saturated uint8 minor + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->minor = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->minor = 0U; + } + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_Version_1_0_initialize_(uavcan_node_Version_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_Version_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_VERSION_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/ID_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/port/ID_1_0.h new file mode 100644 index 0000000..8f759a5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/ID_1_0.h @@ -0,0 +1,306 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ID.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.459347 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.ID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_PORT_ID_1_0_INCLUDED_ +#define UAVCAN_NODE_PORT_ID_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_ID_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.ID.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_ID_1_0_FULL_NAME_ "uavcan.node.port.ID" +#define uavcan_node_port_ID_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.port.ID.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_ID_1_0_EXTENT_BYTES_ 3UL +#define uavcan_node_port_ID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 3UL +static_assert(uavcan_node_port_ID_1_0_EXTENT_BYTES_ >= uavcan_node_port_ID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// uavcan.node.port.SubjectID.1.0 subject_id + uavcan_node_port_SubjectID_1_0 subject_id; + + /// uavcan.node.port.ServiceID.1.0 service_id + uavcan_node_port_ServiceID_1_0 service_id; + }; + uint8_t _tag_; +} uavcan_node_port_ID_1_0; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_node_port_ID_1_0_UNION_OPTION_COUNT_ 2U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_ID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ID_1_0_serialize_( + const uavcan_node_port_ID_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 24UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // uavcan.node.port.SubjectID.1.0 subject_id + { + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_node_port_SubjectID_1_0_serialize_( + &obj->subject_id, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + else if (1U == obj->_tag_) // uavcan.node.port.ServiceID.1.0 service_id + { + size_t _size_bytes1_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_node_port_ServiceID_1_0_serialize_( + &obj->service_id, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ID_1_0_deserialize_( + uavcan_node_port_ID_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // uavcan.node.port.SubjectID.1.0 subject_id + { + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_node_port_SubjectID_1_0_deserialize_( + &out_obj->subject_id, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else if (1U == out_obj->_tag_) // uavcan.node.port.ServiceID.1.0 service_id + { + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_node_port_ServiceID_1_0_deserialize_( + &out_obj->service_id, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_ID_1_0_initialize_(uavcan_node_port_ID_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_ID_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "subject_id" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_ID_1_0_select_subject_id_(uavcan_node_port_ID_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "subject_id" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_ID_1_0_is_subject_id_(const uavcan_node_port_ID_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "service_id" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_ID_1_0_select_service_id_(uavcan_node_port_ID_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "service_id" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_ID_1_0_is_service_id_(const uavcan_node_port_ID_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_ID_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/List_0_1.h b/components/esp_nunavut/nunavut/uavcan/node/port/List_0_1.h new file mode 100644 index 0000000..6b953cf --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/List_0_1.h @@ -0,0 +1,404 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.471763 UTC +// Is deprecated: yes +// Fixed port-ID: 7510 +// Full name: uavcan.node.port.List +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_NODE_PORT_LIST_0_1_INCLUDED_ +#define UAVCAN_NODE_PORT_LIST_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_port_List_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_node_port_List_0_1_FIXED_PORT_ID_ 7510U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.List.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_List_0_1_FULL_NAME_ "uavcan.node.port.List" +#define uavcan_node_port_List_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.port.List.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_List_0_1_EXTENT_BYTES_ 8466UL +#define uavcan_node_port_List_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 8466UL +static_assert(uavcan_node_port_List_0_1_EXTENT_BYTES_ >= uavcan_node_port_List_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_PUBLICATION_PERIOD = 10 +#define uavcan_node_port_List_0_1_MAX_PUBLICATION_PERIOD (10U) + +typedef struct +{ + /// uavcan.node.port.SubjectIDList.0.1 publishers + uavcan_node_port_SubjectIDList_0_1 publishers; + + /// uavcan.node.port.SubjectIDList.0.1 subscribers + uavcan_node_port_SubjectIDList_0_1 subscribers; + + /// uavcan.node.port.ServiceIDList.0.1 clients + uavcan_node_port_ServiceIDList_0_1 clients; + + /// uavcan.node.port.ServiceIDList.0.1 servers + uavcan_node_port_ServiceIDList_0_1 servers; +} uavcan_node_port_List_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_List_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_List_0_1_serialize_( + const uavcan_node_port_List_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 67728UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.node.port.SubjectIDList.0.1 publishers + size_t _size_bytes0_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + int8_t _err0_ = uavcan_node_port_SubjectIDList_0_1_serialize_( + &obj->publishers, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + // Jump back to write the delimiter header after the nested object is serialized and its length is known. + _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits - 32, _size_bytes0_, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.port.SubjectIDList.0.1 subscribers + size_t _size_bytes1_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + int8_t _err2_ = uavcan_node_port_SubjectIDList_0_1_serialize_( + &obj->subscribers, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + // Jump back to write the delimiter header after the nested object is serialized and its length is known. + _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits - 32, _size_bytes1_, 32U); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.node.port.ServiceIDList.0.1 clients + size_t _size_bytes2_ = 64UL; // Nested object (max) size, in bytes. + // Constant delimiter header can be written ahead of the nested object. + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _size_bytes2_, 32U); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 32U; + int8_t _err4_ = uavcan_node_port_ServiceIDList_0_1_serialize_( + &obj->clients, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + } + { // uavcan.node.port.ServiceIDList.0.1 servers + size_t _size_bytes3_ = 64UL; // Nested object (max) size, in bytes. + // Constant delimiter header can be written ahead of the nested object. + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _size_bytes3_, 32U); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += 32U; + int8_t _err7_ = uavcan_node_port_ServiceIDList_0_1_serialize_( + &obj->servers, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_List_0_1_deserialize_( + uavcan_node_port_List_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.node.port.SubjectIDList.0.1 publishers + { + // Delimiter header: truncated uint32 + size_t _size_bytes4_ = 0U; + _size_bytes4_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes4_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh0_ = _size_bytes4_; // Store the original delimiter header value. + const int8_t _err10_ = uavcan_node_port_SubjectIDList_0_1_deserialize_( + &out_obj->publishers, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err10_ < 0) + { + return _err10_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh0_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.port.SubjectIDList.0.1 subscribers + { + // Delimiter header: truncated uint32 + size_t _size_bytes5_ = 0U; + _size_bytes5_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes5_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh1_ = _size_bytes5_; // Store the original delimiter header value. + const int8_t _err11_ = uavcan_node_port_SubjectIDList_0_1_deserialize_( + &out_obj->subscribers, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err11_ < 0) + { + return _err11_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh1_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.port.ServiceIDList.0.1 clients + { + // Delimiter header: truncated uint32 + size_t _size_bytes6_ = 0U; + _size_bytes6_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes6_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh2_ = _size_bytes6_; // Store the original delimiter header value. + const int8_t _err12_ = uavcan_node_port_ServiceIDList_0_1_deserialize_( + &out_obj->clients, &buffer[offset_bits / 8U], &_size_bytes6_); + if (_err12_ < 0) + { + return _err12_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh2_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.port.ServiceIDList.0.1 servers + { + // Delimiter header: truncated uint32 + size_t _size_bytes7_ = 0U; + _size_bytes7_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes7_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh3_ = _size_bytes7_; // Store the original delimiter header value. + const int8_t _err13_ = uavcan_node_port_ServiceIDList_0_1_deserialize_( + &out_obj->servers, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err13_ < 0) + { + return _err13_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh3_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_List_0_1_initialize_(uavcan_node_port_List_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_List_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_LIST_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/List_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/port/List_1_0.h new file mode 100644 index 0000000..6521f6e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/List_1_0.h @@ -0,0 +1,395 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.464581 UTC +// Is deprecated: no +// Fixed port-ID: 7510 +// Full name: uavcan.node.port.List +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_PORT_LIST_1_0_INCLUDED_ +#define UAVCAN_NODE_PORT_LIST_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/7510.List.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_node_port_List_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_node_port_List_1_0_FIXED_PORT_ID_ 7510U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.List.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_List_1_0_FULL_NAME_ "uavcan.node.port.List" +#define uavcan_node_port_List_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.port.List.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_List_1_0_EXTENT_BYTES_ 8466UL +#define uavcan_node_port_List_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 8466UL +static_assert(uavcan_node_port_List_1_0_EXTENT_BYTES_ >= uavcan_node_port_List_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_PUBLICATION_PERIOD = 10 +#define uavcan_node_port_List_1_0_MAX_PUBLICATION_PERIOD (10U) + +typedef struct +{ + /// uavcan.node.port.SubjectIDList.1.0 publishers + uavcan_node_port_SubjectIDList_1_0 publishers; + + /// uavcan.node.port.SubjectIDList.1.0 subscribers + uavcan_node_port_SubjectIDList_1_0 subscribers; + + /// uavcan.node.port.ServiceIDList.1.0 clients + uavcan_node_port_ServiceIDList_1_0 clients; + + /// uavcan.node.port.ServiceIDList.1.0 servers + uavcan_node_port_ServiceIDList_1_0 servers; +} uavcan_node_port_List_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_List_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_List_1_0_serialize_( + const uavcan_node_port_List_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 67728UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.node.port.SubjectIDList.1.0 publishers + size_t _size_bytes0_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + int8_t _err0_ = uavcan_node_port_SubjectIDList_1_0_serialize_( + &obj->publishers, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + // Jump back to write the delimiter header after the nested object is serialized and its length is known. + _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits - 32, _size_bytes0_, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.port.SubjectIDList.1.0 subscribers + size_t _size_bytes1_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + int8_t _err2_ = uavcan_node_port_SubjectIDList_1_0_serialize_( + &obj->subscribers, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + // Jump back to write the delimiter header after the nested object is serialized and its length is known. + _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits - 32, _size_bytes1_, 32U); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.node.port.ServiceIDList.1.0 clients + size_t _size_bytes2_ = 64UL; // Nested object (max) size, in bytes. + // Constant delimiter header can be written ahead of the nested object. + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _size_bytes2_, 32U); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 32U; + int8_t _err4_ = uavcan_node_port_ServiceIDList_1_0_serialize_( + &obj->clients, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + } + { // uavcan.node.port.ServiceIDList.1.0 servers + size_t _size_bytes3_ = 64UL; // Nested object (max) size, in bytes. + // Constant delimiter header can be written ahead of the nested object. + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _size_bytes3_, 32U); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += 32U; + int8_t _err7_ = uavcan_node_port_ServiceIDList_1_0_serialize_( + &obj->servers, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_List_1_0_deserialize_( + uavcan_node_port_List_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.node.port.SubjectIDList.1.0 publishers + { + // Delimiter header: truncated uint32 + size_t _size_bytes4_ = 0U; + _size_bytes4_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes4_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh0_ = _size_bytes4_; // Store the original delimiter header value. + const int8_t _err10_ = uavcan_node_port_SubjectIDList_1_0_deserialize_( + &out_obj->publishers, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err10_ < 0) + { + return _err10_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh0_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.port.SubjectIDList.1.0 subscribers + { + // Delimiter header: truncated uint32 + size_t _size_bytes5_ = 0U; + _size_bytes5_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes5_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh1_ = _size_bytes5_; // Store the original delimiter header value. + const int8_t _err11_ = uavcan_node_port_SubjectIDList_1_0_deserialize_( + &out_obj->subscribers, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err11_ < 0) + { + return _err11_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh1_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.port.ServiceIDList.1.0 clients + { + // Delimiter header: truncated uint32 + size_t _size_bytes6_ = 0U; + _size_bytes6_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes6_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh2_ = _size_bytes6_; // Store the original delimiter header value. + const int8_t _err12_ = uavcan_node_port_ServiceIDList_1_0_deserialize_( + &out_obj->clients, &buffer[offset_bits / 8U], &_size_bytes6_); + if (_err12_ < 0) + { + return _err12_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh2_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.port.ServiceIDList.1.0 servers + { + // Delimiter header: truncated uint32 + size_t _size_bytes7_ = 0U; + _size_bytes7_ = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + if (_size_bytes7_ > (capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes))) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_DELIMITER_HEADER; + } + const size_t _dh3_ = _size_bytes7_; // Store the original delimiter header value. + const int8_t _err13_ = uavcan_node_port_ServiceIDList_1_0_deserialize_( + &out_obj->servers, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err13_ < 0) + { + return _err13_; + } + // Advance the offset by the size of the delimiter header, even if the nested deserialization routine + // consumed fewer bytes of data. This behavior implements the implicit truncation rule for nested objects. + offset_bits += _dh3_ * 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_List_1_0_initialize_(uavcan_node_port_List_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_List_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_LIST_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_0_1.h b/components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_0_1.h new file mode 100644 index 0000000..63fe152 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_0_1.h @@ -0,0 +1,219 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.485718 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.node.port.ServiceIDList +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_NODE_PORT_SERVICE_ID_LIST_0_1_INCLUDED_ +#define UAVCAN_NODE_PORT_SERVICE_ID_LIST_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_ServiceIDList_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.ServiceIDList.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_ServiceIDList_0_1_FULL_NAME_ "uavcan.node.port.ServiceIDList" +#define uavcan_node_port_ServiceIDList_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.port.ServiceIDList.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_ServiceIDList_0_1_EXTENT_BYTES_ 128UL +#define uavcan_node_port_ServiceIDList_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 64UL +static_assert(uavcan_node_port_ServiceIDList_0_1_EXTENT_BYTES_ >= uavcan_node_port_ServiceIDList_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 CAPACITY = 512 +#define uavcan_node_port_ServiceIDList_0_1_CAPACITY (512U) + +/// Array metadata for: saturated bool[512] mask +#define uavcan_node_port_ServiceIDList_0_1_mask_ARRAY_CAPACITY_ 512U +#define uavcan_node_port_ServiceIDList_0_1_mask_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated bool[512] mask + /// Bitpacked array, capacity 512 bits. Access via @ref nunavutSetBit(), @ref nunavutGetBit(). + uint8_t mask_bitpacked_[64]; +} uavcan_node_port_ServiceIDList_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_ServiceIDList_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ServiceIDList_0_1_serialize_( + const uavcan_node_port_ServiceIDList_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 512UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated bool[512] mask + // Optimization prospect: this item is aligned at the byte boundary, so it is possible to use memmove(). + nunavutCopyBits(&buffer[0], offset_bits, 512UL, &obj->mask_bitpacked_[0], 0U); + offset_bits += 512UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ServiceIDList_0_1_deserialize_( + uavcan_node_port_ServiceIDList_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated bool[512] mask + nunavutGetBits(&out_obj->mask_bitpacked_[0], &buffer[0], capacity_bytes, offset_bits, 512UL); + offset_bits += 512UL; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_ServiceIDList_0_1_initialize_(uavcan_node_port_ServiceIDList_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_ServiceIDList_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SERVICE_ID_LIST_0_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_1_0.h new file mode 100644 index 0000000..af221e7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/ServiceIDList_1_0.h @@ -0,0 +1,210 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.482150 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.ServiceIDList +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_PORT_SERVICE_ID_LIST_1_0_INCLUDED_ +#define UAVCAN_NODE_PORT_SERVICE_ID_LIST_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_ServiceIDList_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.ServiceIDList.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_ServiceIDList_1_0_FULL_NAME_ "uavcan.node.port.ServiceIDList" +#define uavcan_node_port_ServiceIDList_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.port.ServiceIDList.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_ServiceIDList_1_0_EXTENT_BYTES_ 128UL +#define uavcan_node_port_ServiceIDList_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 64UL +static_assert(uavcan_node_port_ServiceIDList_1_0_EXTENT_BYTES_ >= uavcan_node_port_ServiceIDList_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 CAPACITY = 512 +#define uavcan_node_port_ServiceIDList_1_0_CAPACITY (512U) + +/// Array metadata for: saturated bool[512] mask +#define uavcan_node_port_ServiceIDList_1_0_mask_ARRAY_CAPACITY_ 512U +#define uavcan_node_port_ServiceIDList_1_0_mask_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated bool[512] mask + /// Bitpacked array, capacity 512 bits. Access via @ref nunavutSetBit(), @ref nunavutGetBit(). + uint8_t mask_bitpacked_[64]; +} uavcan_node_port_ServiceIDList_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_ServiceIDList_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ServiceIDList_1_0_serialize_( + const uavcan_node_port_ServiceIDList_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 512UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated bool[512] mask + // Optimization prospect: this item is aligned at the byte boundary, so it is possible to use memmove(). + nunavutCopyBits(&buffer[0], offset_bits, 512UL, &obj->mask_bitpacked_[0], 0U); + offset_bits += 512UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ServiceIDList_1_0_deserialize_( + uavcan_node_port_ServiceIDList_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated bool[512] mask + nunavutGetBits(&out_obj->mask_bitpacked_[0], &buffer[0], capacity_bytes, offset_bits, 512UL); + offset_bits += 512UL; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_ServiceIDList_1_0_initialize_(uavcan_node_port_ServiceIDList_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_ServiceIDList_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SERVICE_ID_LIST_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/ServiceID_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/port/ServiceID_1_0.h new file mode 100644 index 0000000..1e444b2 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/ServiceID_1_0.h @@ -0,0 +1,211 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceID.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.478666 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.ServiceID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_PORT_SERVICE_ID_1_0_INCLUDED_ +#define UAVCAN_NODE_PORT_SERVICE_ID_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/ServiceID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_ServiceID_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.ServiceID.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_ServiceID_1_0_FULL_NAME_ "uavcan.node.port.ServiceID" +#define uavcan_node_port_ServiceID_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.port.ServiceID.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_ServiceID_1_0_EXTENT_BYTES_ 2UL +#define uavcan_node_port_ServiceID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_node_port_ServiceID_1_0_EXTENT_BYTES_ >= uavcan_node_port_ServiceID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint9 MAX = 511 +#define uavcan_node_port_ServiceID_1_0_MAX (511U) + +typedef struct +{ + /// saturated uint9 value + uint16_t value; +} uavcan_node_port_ServiceID_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_ServiceID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ServiceID_1_0_serialize_( + const uavcan_node_port_ServiceID_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint9 value + uint16_t _sat0_ = obj->value; + if (_sat0_ > 511U) + { + _sat0_ = 511U; + } + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _sat0_, 9U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 9U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_ServiceID_1_0_deserialize_( + uavcan_node_port_ServiceID_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint9 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 9); + offset_bits += 9U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_ServiceID_1_0_initialize_(uavcan_node_port_ServiceID_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_ServiceID_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SERVICE_ID_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_0_1.h b/components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_0_1.h new file mode 100644 index 0000000..36d560e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_0_1.h @@ -0,0 +1,388 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.499103 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.node.port.SubjectIDList +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_NODE_PORT_SUBJECT_ID_LIST_0_1_INCLUDED_ +#define UAVCAN_NODE_PORT_SUBJECT_ID_LIST_0_1_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_SubjectIDList_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.SubjectIDList.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_SubjectIDList_0_1_FULL_NAME_ "uavcan.node.port.SubjectIDList" +#define uavcan_node_port_SubjectIDList_0_1_FULL_NAME_AND_VERSION_ "uavcan.node.port.SubjectIDList.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_SubjectIDList_0_1_EXTENT_BYTES_ 4097UL +#define uavcan_node_port_SubjectIDList_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 1025UL +static_assert(uavcan_node_port_SubjectIDList_0_1_EXTENT_BYTES_ >= uavcan_node_port_SubjectIDList_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 CAPACITY = 8192 +#define uavcan_node_port_SubjectIDList_0_1_CAPACITY (8192U) + +/// Array metadata for: saturated bool[8192] mask +#define uavcan_node_port_SubjectIDList_0_1_mask_ARRAY_CAPACITY_ 8192U +#define uavcan_node_port_SubjectIDList_0_1_mask_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: uavcan.node.port.SubjectID.1.0[<=255] sparse_list +#define uavcan_node_port_SubjectIDList_0_1_sparse_list_ARRAY_CAPACITY_ 255U +#define uavcan_node_port_SubjectIDList_0_1_sparse_list_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// saturated bool[8192] mask + /// Bitpacked array, capacity 8192 bits. Access via @ref nunavutSetBit(), @ref nunavutGetBit(). + uint8_t mask_bitpacked_[1024]; + + /// uavcan.node.port.SubjectID.1.0[<=255] sparse_list + struct /// Array address equivalence guarantee: &elements[0] == &sparse_list + { + uavcan_node_port_SubjectID_1_0 elements[uavcan_node_port_SubjectIDList_0_1_sparse_list_ARRAY_CAPACITY_]; + size_t count; + } sparse_list; + + /// uavcan.primitive.Empty.1.0 total + uavcan_primitive_Empty_1_0 _total; + }; + uint8_t _tag_; +} uavcan_node_port_SubjectIDList_0_1; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_node_port_SubjectIDList_0_1_UNION_OPTION_COUNT_ 3U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_SubjectIDList_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_SubjectIDList_0_1_serialize_( + const uavcan_node_port_SubjectIDList_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8200UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // saturated bool[8192] mask + { + // Optimization prospect: this item is aligned at the byte boundary, so it is possible to use memmove(). + nunavutCopyBits(&buffer[0], offset_bits, 8192UL, &obj->mask_bitpacked_[0], 0U); + offset_bits += 8192UL; + } + else if (1U == obj->_tag_) // uavcan.node.port.SubjectID.1.0[<=255] sparse_list + { + if (obj->sparse_list.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->sparse_list.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->sparse_list.count; ++_index0_) + { + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_node_port_SubjectID_1_0_serialize_( + &obj->sparse_list.elements[_index0_], &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + } + else if (2U == obj->_tag_) // uavcan.primitive.Empty.1.0 total + { + size_t _size_bytes1_ = 0UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_primitive_Empty_1_0_serialize_( + &obj->_total, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_SubjectIDList_0_1_deserialize_( + uavcan_node_port_SubjectIDList_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // saturated bool[8192] mask + { + nunavutGetBits(&out_obj->mask_bitpacked_[0], &buffer[0], capacity_bytes, offset_bits, 8192UL); + offset_bits += 8192UL; + } + else if (1U == out_obj->_tag_) // uavcan.node.port.SubjectID.1.0[<=255] sparse_list + { + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->sparse_list.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->sparse_list.count = 0U; + } + offset_bits += 8U; + if (out_obj->sparse_list.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->sparse_list.count; ++_index1_) + { + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_node_port_SubjectID_1_0_deserialize_( + &out_obj->sparse_list.elements[_index1_], &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + } + } + else if (2U == out_obj->_tag_) // uavcan.primitive.Empty.1.0 total + { + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_primitive_Empty_1_0_deserialize_( + &out_obj->_total, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_SubjectIDList_0_1_initialize_(uavcan_node_port_SubjectIDList_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_SubjectIDList_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "mask" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_SubjectIDList_0_1_select_mask_(uavcan_node_port_SubjectIDList_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "mask" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_SubjectIDList_0_1_is_mask_(const uavcan_node_port_SubjectIDList_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "sparse_list" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_SubjectIDList_0_1_select_sparse_list_(uavcan_node_port_SubjectIDList_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "sparse_list" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_SubjectIDList_0_1_is_sparse_list_(const uavcan_node_port_SubjectIDList_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +/// Mark option "total" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_SubjectIDList_0_1_select_total_(uavcan_node_port_SubjectIDList_0_1* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 2; + } +} + +/// Check if option "total" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_SubjectIDList_0_1_is_total_(const uavcan_node_port_SubjectIDList_0_1* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 2)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SUBJECT_ID_LIST_0_1_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_1_0.h new file mode 100644 index 0000000..4876524 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/SubjectIDList_1_0.h @@ -0,0 +1,379 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.492655 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.SubjectIDList +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_PORT_SUBJECT_ID_LIST_1_0_INCLUDED_ +#define UAVCAN_NODE_PORT_SUBJECT_ID_LIST_1_0_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectIDList.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_SubjectIDList_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.SubjectIDList.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_SubjectIDList_1_0_FULL_NAME_ "uavcan.node.port.SubjectIDList" +#define uavcan_node_port_SubjectIDList_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.port.SubjectIDList.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_SubjectIDList_1_0_EXTENT_BYTES_ 4097UL +#define uavcan_node_port_SubjectIDList_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1025UL +static_assert(uavcan_node_port_SubjectIDList_1_0_EXTENT_BYTES_ >= uavcan_node_port_SubjectIDList_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint16 CAPACITY = 8192 +#define uavcan_node_port_SubjectIDList_1_0_CAPACITY (8192U) + +/// Array metadata for: saturated bool[8192] mask +#define uavcan_node_port_SubjectIDList_1_0_mask_ARRAY_CAPACITY_ 8192U +#define uavcan_node_port_SubjectIDList_1_0_mask_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: uavcan.node.port.SubjectID.1.0[<=255] sparse_list +#define uavcan_node_port_SubjectIDList_1_0_sparse_list_ARRAY_CAPACITY_ 255U +#define uavcan_node_port_SubjectIDList_1_0_sparse_list_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + union /// The union is placed first to ensure that the active element address equals the struct address. + { + /// saturated bool[8192] mask + /// Bitpacked array, capacity 8192 bits. Access via @ref nunavutSetBit(), @ref nunavutGetBit(). + uint8_t mask_bitpacked_[1024]; + + /// uavcan.node.port.SubjectID.1.0[<=255] sparse_list + struct /// Array address equivalence guarantee: &elements[0] == &sparse_list + { + uavcan_node_port_SubjectID_1_0 elements[uavcan_node_port_SubjectIDList_1_0_sparse_list_ARRAY_CAPACITY_]; + size_t count; + } sparse_list; + + /// uavcan.primitive.Empty.1.0 total + uavcan_primitive_Empty_1_0 _total; + }; + uint8_t _tag_; +} uavcan_node_port_SubjectIDList_1_0; + +/// The number of fields in the union. Valid tag values range from zero to this value minus one, inclusive. +#define uavcan_node_port_SubjectIDList_1_0_UNION_OPTION_COUNT_ 3U + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_SubjectIDList_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_SubjectIDList_1_0_serialize_( + const uavcan_node_port_SubjectIDList_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8200UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // Union tag field: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->_tag_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (0U == obj->_tag_) // saturated bool[8192] mask + { + // Optimization prospect: this item is aligned at the byte boundary, so it is possible to use memmove(). + nunavutCopyBits(&buffer[0], offset_bits, 8192UL, &obj->mask_bitpacked_[0], 0U); + offset_bits += 8192UL; + } + else if (1U == obj->_tag_) // uavcan.node.port.SubjectID.1.0[<=255] sparse_list + { + if (obj->sparse_list.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->sparse_list.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->sparse_list.count; ++_index0_) + { + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_node_port_SubjectID_1_0_serialize_( + &obj->sparse_list.elements[_index0_], &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + } + else if (2U == obj->_tag_) // uavcan.primitive.Empty.1.0 total + { + size_t _size_bytes1_ = 0UL; // Nested object (max) size, in bytes. + int8_t _err1_ = uavcan_primitive_Empty_1_0_serialize_( + &obj->_total, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err1_ < 0) + { + return _err1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_SubjectIDList_1_0_deserialize_( + uavcan_node_port_SubjectIDList_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // Union tag field: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->_tag_ = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->_tag_ = 0U; + } + offset_bits += 8U; + if (0U == out_obj->_tag_) // saturated bool[8192] mask + { + nunavutGetBits(&out_obj->mask_bitpacked_[0], &buffer[0], capacity_bytes, offset_bits, 8192UL); + offset_bits += 8192UL; + } + else if (1U == out_obj->_tag_) // uavcan.node.port.SubjectID.1.0[<=255] sparse_list + { + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->sparse_list.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->sparse_list.count = 0U; + } + offset_bits += 8U; + if (out_obj->sparse_list.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->sparse_list.count; ++_index1_) + { + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_node_port_SubjectID_1_0_deserialize_( + &out_obj->sparse_list.elements[_index1_], &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + } + } + else if (2U == out_obj->_tag_) // uavcan.primitive.Empty.1.0 total + { + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_primitive_Empty_1_0_deserialize_( + &out_obj->_total, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + } + else + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_UNION_TAG; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_SubjectIDList_1_0_initialize_(uavcan_node_port_SubjectIDList_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_SubjectIDList_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} +/// Mark option "mask" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_SubjectIDList_1_0_select_mask_(uavcan_node_port_SubjectIDList_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 0; + } +} + +/// Check if option "mask" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_SubjectIDList_1_0_is_mask_(const uavcan_node_port_SubjectIDList_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 0)); +} + +/// Mark option "sparse_list" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_SubjectIDList_1_0_select_sparse_list_(uavcan_node_port_SubjectIDList_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 1; + } +} + +/// Check if option "sparse_list" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_SubjectIDList_1_0_is_sparse_list_(const uavcan_node_port_SubjectIDList_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 1)); +} + +/// Mark option "total" active without initializing it. Does nothing if @param obj is NULL. +static inline void uavcan_node_port_SubjectIDList_1_0_select_total_(uavcan_node_port_SubjectIDList_1_0* const obj) +{ + if (obj != NULL) + { + obj->_tag_ = 2; + } +} + +/// Check if option "total" is active. Returns false if @param obj is NULL. +static inline bool uavcan_node_port_SubjectIDList_1_0_is_total_(const uavcan_node_port_SubjectIDList_1_0* const obj) +{ + return ((obj != NULL) && (obj->_tag_ == 2)); +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SUBJECT_ID_LIST_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/node/port/SubjectID_1_0.h b/components/esp_nunavut/nunavut/uavcan/node/port/SubjectID_1_0.h new file mode 100644 index 0000000..5d09ad8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/node/port/SubjectID_1_0.h @@ -0,0 +1,211 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectID.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.489164 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.SubjectID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_NODE_PORT_SUBJECT_ID_1_0_INCLUDED_ +#define UAVCAN_NODE_PORT_SUBJECT_ID_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/node/port/SubjectID.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_node_port_SubjectID_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.node.port.SubjectID.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_node_port_SubjectID_1_0_FULL_NAME_ "uavcan.node.port.SubjectID" +#define uavcan_node_port_SubjectID_1_0_FULL_NAME_AND_VERSION_ "uavcan.node.port.SubjectID.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_node_port_SubjectID_1_0_EXTENT_BYTES_ 2UL +#define uavcan_node_port_SubjectID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_node_port_SubjectID_1_0_EXTENT_BYTES_ >= uavcan_node_port_SubjectID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint13 MAX = 8191 +#define uavcan_node_port_SubjectID_1_0_MAX (8191U) + +typedef struct +{ + /// saturated uint13 value + uint16_t value; +} uavcan_node_port_SubjectID_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_node_port_SubjectID_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_SubjectID_1_0_serialize_( + const uavcan_node_port_SubjectID_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint13 value + uint16_t _sat0_ = obj->value; + if (_sat0_ > 8191U) + { + _sat0_ = 8191U; + } + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _sat0_, 13U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 13U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_node_port_SubjectID_1_0_deserialize_( + uavcan_node_port_SubjectID_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint13 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 13); + offset_bits += 13U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_node_port_SubjectID_1_0_initialize_(uavcan_node_port_SubjectID_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_node_port_SubjectID_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SUBJECT_ID_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_1_0.h b/components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_1_0.h new file mode 100644 index 0000000..7e6fba7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_1_0.h @@ -0,0 +1,275 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.354401 UTC +// Is deprecated: no +// Fixed port-ID: 8166 +// Full name: uavcan.pnp.NodeIDAllocationData +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_1_0_INCLUDED_ +#define UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_pnp_NodeIDAllocationData_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_pnp_NodeIDAllocationData_1_0_FIXED_PORT_ID_ 8166U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.NodeIDAllocationData.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_NodeIDAllocationData_1_0_FULL_NAME_ "uavcan.pnp.NodeIDAllocationData" +#define uavcan_pnp_NodeIDAllocationData_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.NodeIDAllocationData.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_NodeIDAllocationData_1_0_EXTENT_BYTES_ 9UL +#define uavcan_pnp_NodeIDAllocationData_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 9UL +static_assert(uavcan_pnp_NodeIDAllocationData_1_0_EXTENT_BYTES_ >= uavcan_pnp_NodeIDAllocationData_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: uavcan.node.ID.1.0[<=1] allocated_node_id +#define uavcan_pnp_NodeIDAllocationData_1_0_allocated_node_id_ARRAY_CAPACITY_ 1U +#define uavcan_pnp_NodeIDAllocationData_1_0_allocated_node_id_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// truncated uint48 unique_id_hash + uint64_t unique_id_hash; + + /// uavcan.node.ID.1.0[<=1] allocated_node_id + struct /// Array address equivalence guarantee: &elements[0] == &allocated_node_id + { + uavcan_node_ID_1_0 elements[uavcan_pnp_NodeIDAllocationData_1_0_allocated_node_id_ARRAY_CAPACITY_]; + size_t count; + } allocated_node_id; +} uavcan_pnp_NodeIDAllocationData_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_NodeIDAllocationData_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_NodeIDAllocationData_1_0_serialize_( + const uavcan_pnp_NodeIDAllocationData_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 72UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint48 unique_id_hash + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->unique_id_hash, 48U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 48U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.ID.1.0[<=1] allocated_node_id + if (obj->allocated_node_id.count > 1) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->allocated_node_id.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->allocated_node_id.count; ++_index0_) + { + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_node_ID_1_0_serialize_( + &obj->allocated_node_id.elements[_index0_], &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_NodeIDAllocationData_1_0_deserialize_( + uavcan_pnp_NodeIDAllocationData_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint48 unique_id_hash + out_obj->unique_id_hash = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 48); + offset_bits += 48U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.ID.1.0[<=1] allocated_node_id + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->allocated_node_id.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->allocated_node_id.count = 0U; + } + offset_bits += 8U; + if (out_obj->allocated_node_id.count > 1U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->allocated_node_id.count; ++_index1_) + { + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_node_ID_1_0_deserialize_( + &out_obj->allocated_node_id.elements[_index1_], &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_NodeIDAllocationData_1_0_initialize_(uavcan_pnp_NodeIDAllocationData_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_NodeIDAllocationData_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_2_0.h b/components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_2_0.h new file mode 100644 index 0000000..f6e237b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/pnp/NodeIDAllocationData_2_0.h @@ -0,0 +1,248 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl +// Generated at: 2024-09-11 21:29:53.349637 UTC +// Is deprecated: no +// Fixed port-ID: 8165 +// Full name: uavcan.pnp.NodeIDAllocationData +// Version: 2.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_2_0_INCLUDED_ +#define UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_2_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_pnp_NodeIDAllocationData_2_0_HAS_FIXED_PORT_ID_ true +#define uavcan_pnp_NodeIDAllocationData_2_0_FIXED_PORT_ID_ 8165U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.NodeIDAllocationData.2.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_NodeIDAllocationData_2_0_FULL_NAME_ "uavcan.pnp.NodeIDAllocationData" +#define uavcan_pnp_NodeIDAllocationData_2_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.NodeIDAllocationData.2.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_NodeIDAllocationData_2_0_EXTENT_BYTES_ 48UL +#define uavcan_pnp_NodeIDAllocationData_2_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 18UL +static_assert(uavcan_pnp_NodeIDAllocationData_2_0_EXTENT_BYTES_ >= uavcan_pnp_NodeIDAllocationData_2_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[16] unique_id +#define uavcan_pnp_NodeIDAllocationData_2_0_unique_id_ARRAY_CAPACITY_ 16U +#define uavcan_pnp_NodeIDAllocationData_2_0_unique_id_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.node.ID.1.0 node_id + uavcan_node_ID_1_0 node_id; + + /// saturated uint8[16] unique_id + uint8_t unique_id[16]; +} uavcan_pnp_NodeIDAllocationData_2_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_NodeIDAllocationData_2_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_NodeIDAllocationData_2_0_serialize_( + const uavcan_pnp_NodeIDAllocationData_2_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 144UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.node.ID.1.0 node_id + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_node_ID_1_0_serialize_( + &obj->node_id, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated uint8[16] unique_id + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->unique_id[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_NodeIDAllocationData_2_0_deserialize_( + uavcan_pnp_NodeIDAllocationData_2_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.node.ID.1.0 node_id + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err2_ = uavcan_node_ID_1_0_deserialize_( + &out_obj->node_id, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint8[16] unique_id + for (size_t _index1_ = 0U; _index1_ < 16UL; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->unique_id[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->unique_id[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_NodeIDAllocationData_2_0_initialize_(uavcan_pnp_NodeIDAllocationData_2_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_2_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/pnp/cluster/AppendEntries_1_0.h b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/AppendEntries_1_0.h new file mode 100644 index 0000000..453fc72 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/AppendEntries_1_0.h @@ -0,0 +1,487 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.359391 UTC +// Is deprecated: no +// Fixed port-ID: 390 +// Full name: uavcan.pnp.cluster.AppendEntries +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PNP_CLUSTER_APPEND_ENTRIES_1_0_INCLUDED_ +#define UAVCAN_PNP_CLUSTER_APPEND_ENTRIES_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_pnp_cluster_AppendEntries_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_pnp_cluster_AppendEntries_1_0_FIXED_PORT_ID_ 390U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.AppendEntries.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_AppendEntries_1_0_FULL_NAME_ "uavcan.pnp.cluster.AppendEntries" +#define uavcan_pnp_cluster_AppendEntries_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.AppendEntries.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.AppendEntries.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_FULL_NAME_ "uavcan.pnp.cluster.AppendEntries.Request" +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.AppendEntries.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_EXTENT_BYTES_ 96UL +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 35UL +static_assert(uavcan_pnp_cluster_AppendEntries_Request_1_0_EXTENT_BYTES_ >= uavcan_pnp_cluster_AppendEntries_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 DEFAULT_MIN_ELECTION_TIMEOUT = 2 +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_DEFAULT_MIN_ELECTION_TIMEOUT (2U) + +/// saturated uint8 DEFAULT_MAX_ELECTION_TIMEOUT = 4 +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_DEFAULT_MAX_ELECTION_TIMEOUT (4U) + +/// Array metadata for: uavcan.pnp.cluster.Entry.1.0[<=1] entries +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_entries_ARRAY_CAPACITY_ 1U +#define uavcan_pnp_cluster_AppendEntries_Request_1_0_entries_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint32 term + uint32_t term; + + /// saturated uint32 prev_log_term + uint32_t prev_log_term; + + /// saturated uint16 prev_log_index + uint16_t prev_log_index; + + /// saturated uint16 leader_commit + uint16_t leader_commit; + + /// uavcan.pnp.cluster.Entry.1.0[<=1] entries + struct /// Array address equivalence guarantee: &elements[0] == &entries + { + uavcan_pnp_cluster_Entry_1_0 elements[uavcan_pnp_cluster_AppendEntries_Request_1_0_entries_ARRAY_CAPACITY_]; + size_t count; + } entries; +} uavcan_pnp_cluster_AppendEntries_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_cluster_AppendEntries_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_AppendEntries_Request_1_0_serialize_( + const uavcan_pnp_cluster_AppendEntries_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 280UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->term, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + { // saturated uint32 prev_log_term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->prev_log_term, 32U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + { // saturated uint16 prev_log_index + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->prev_log_index, 16U); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 16U; + } + { // saturated uint16 leader_commit + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->leader_commit, 16U); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + } + { // uavcan.pnp.cluster.Entry.1.0[<=1] entries + if (obj->entries.count > 1) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->entries.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->entries.count; ++_index0_) + { + size_t _size_bytes0_ = 22UL; // Nested object (max) size, in bytes. + int8_t _err5_ = uavcan_pnp_cluster_Entry_1_0_serialize_( + &obj->entries.elements[_index0_], &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err5_ < 0) + { + return _err5_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_AppendEntries_Request_1_0_deserialize_( + uavcan_pnp_cluster_AppendEntries_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 term + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint32 prev_log_term + out_obj->prev_log_term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint16 prev_log_index + out_obj->prev_log_index = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint16 leader_commit + out_obj->leader_commit = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.pnp.cluster.Entry.1.0[<=1] entries + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->entries.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->entries.count = 0U; + } + offset_bits += 8U; + if (out_obj->entries.count > 1U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->entries.count; ++_index1_) + { + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_pnp_cluster_Entry_1_0_deserialize_( + &out_obj->entries.elements[_index1_], &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_cluster_AppendEntries_Request_1_0_initialize_(uavcan_pnp_cluster_AppendEntries_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_cluster_AppendEntries_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.AppendEntries.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_AppendEntries_Response_1_0_FULL_NAME_ "uavcan.pnp.cluster.AppendEntries.Response" +#define uavcan_pnp_cluster_AppendEntries_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.AppendEntries.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_cluster_AppendEntries_Response_1_0_EXTENT_BYTES_ 48UL +#define uavcan_pnp_cluster_AppendEntries_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 5UL +static_assert(uavcan_pnp_cluster_AppendEntries_Response_1_0_EXTENT_BYTES_ >= uavcan_pnp_cluster_AppendEntries_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint32 term + uint32_t term; + + /// saturated bool success + bool success; +} uavcan_pnp_cluster_AppendEntries_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_cluster_AppendEntries_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_AppendEntries_Response_1_0_serialize_( + const uavcan_pnp_cluster_AppendEntries_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 40UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->term, 32U); + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += 32U; + } + { // saturated bool success + buffer[offset_bits / 8U] = obj->success ? 1U : 0U; + offset_bits += 1U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_AppendEntries_Response_1_0_deserialize_( + uavcan_pnp_cluster_AppendEntries_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 term + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated bool success + if (offset_bits < capacity_bits) + { + out_obj->success = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->success = false; + } + offset_bits += 1U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_cluster_AppendEntries_Response_1_0_initialize_(uavcan_pnp_cluster_AppendEntries_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_cluster_AppendEntries_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_APPEND_ENTRIES_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/pnp/cluster/Discovery_1_0.h b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/Discovery_1_0.h new file mode 100644 index 0000000..2d3c0be --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/Discovery_1_0.h @@ -0,0 +1,300 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.368580 UTC +// Is deprecated: no +// Fixed port-ID: 8164 +// Full name: uavcan.pnp.cluster.Discovery +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PNP_CLUSTER_DISCOVERY_1_0_INCLUDED_ +#define UAVCAN_PNP_CLUSTER_DISCOVERY_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_pnp_cluster_Discovery_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_pnp_cluster_Discovery_1_0_FIXED_PORT_ID_ 8164U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.Discovery.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_Discovery_1_0_FULL_NAME_ "uavcan.pnp.cluster.Discovery" +#define uavcan_pnp_cluster_Discovery_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.Discovery.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_cluster_Discovery_1_0_EXTENT_BYTES_ 96UL +#define uavcan_pnp_cluster_Discovery_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_pnp_cluster_Discovery_1_0_EXTENT_BYTES_ >= uavcan_pnp_cluster_Discovery_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 BROADCASTING_PERIOD = 1 +#define uavcan_pnp_cluster_Discovery_1_0_BROADCASTING_PERIOD (1U) + +/// saturated uint3 MAX_CLUSTER_SIZE = 5 +#define uavcan_pnp_cluster_Discovery_1_0_MAX_CLUSTER_SIZE (5U) + +/// Array metadata for: uavcan.node.ID.1.0[<=5] known_nodes +#define uavcan_pnp_cluster_Discovery_1_0_known_nodes_ARRAY_CAPACITY_ 5U +#define uavcan_pnp_cluster_Discovery_1_0_known_nodes_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint3 configured_cluster_size + uint8_t configured_cluster_size; + + /// uavcan.node.ID.1.0[<=5] known_nodes + struct /// Array address equivalence guarantee: &elements[0] == &known_nodes + { + uavcan_node_ID_1_0 elements[uavcan_pnp_cluster_Discovery_1_0_known_nodes_ARRAY_CAPACITY_]; + size_t count; + } known_nodes; +} uavcan_pnp_cluster_Discovery_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_cluster_Discovery_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_Discovery_1_0_serialize_( + const uavcan_pnp_cluster_Discovery_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint3 configured_cluster_size + uint8_t _sat0_ = obj->configured_cluster_size; + if (_sat0_ > 7U) + { + _sat0_ = 7U; + } + buffer[offset_bits / 8U] = (uint8_t)(_sat0_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 3U; + } + { // void5 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 5U); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 5UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.ID.1.0[<=5] known_nodes + if (obj->known_nodes.count > 5) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->known_nodes.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->known_nodes.count; ++_index0_) + { + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_node_ID_1_0_serialize_( + &obj->known_nodes.elements[_index0_], &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_Discovery_1_0_deserialize_( + uavcan_pnp_cluster_Discovery_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint3 configured_cluster_size + if ((offset_bits + 3U) <= capacity_bits) + { + out_obj->configured_cluster_size = buffer[offset_bits / 8U] & 7U; + } + else + { + out_obj->configured_cluster_size = 0U; + } + offset_bits += 3U; + // void5 + offset_bits += 5; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.ID.1.0[<=5] known_nodes + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->known_nodes.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->known_nodes.count = 0U; + } + offset_bits += 8U; + if (out_obj->known_nodes.count > 5U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->known_nodes.count; ++_index1_) + { + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_node_ID_1_0_deserialize_( + &out_obj->known_nodes.elements[_index1_], &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_cluster_Discovery_1_0_initialize_(uavcan_pnp_cluster_Discovery_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_cluster_Discovery_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_DISCOVERY_1_0_INCLUDED_ + diff --git a/components/esp_nunavut/nunavut/uavcan/pnp/cluster/Entry_1_0.h b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/Entry_1_0.h new file mode 100644 index 0000000..3786511 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/Entry_1_0.h @@ -0,0 +1,273 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/Entry.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.374166 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.pnp.cluster.Entry +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PNP_CLUSTER_ENTRY_1_0_INCLUDED_ +#define UAVCAN_PNP_CLUSTER_ENTRY_1_0_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/Entry.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/Entry.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/Entry.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/Entry.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/Entry.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_pnp_cluster_Entry_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.Entry.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_Entry_1_0_FULL_NAME_ "uavcan.pnp.cluster.Entry" +#define uavcan_pnp_cluster_Entry_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.Entry.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_cluster_Entry_1_0_EXTENT_BYTES_ 22UL +#define uavcan_pnp_cluster_Entry_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 22UL +static_assert(uavcan_pnp_cluster_Entry_1_0_EXTENT_BYTES_ >= uavcan_pnp_cluster_Entry_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[16] unique_id +#define uavcan_pnp_cluster_Entry_1_0_unique_id_ARRAY_CAPACITY_ 16U +#define uavcan_pnp_cluster_Entry_1_0_unique_id_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated uint32 term + uint32_t term; + + /// saturated uint8[16] unique_id + uint8_t unique_id[16]; + + /// uavcan.node.ID.1.0 node_id + uavcan_node_ID_1_0 node_id; +} uavcan_pnp_cluster_Entry_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_cluster_Entry_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_Entry_1_0_serialize_( + const uavcan_pnp_cluster_Entry_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 176UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->term, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + { // saturated uint8[16] unique_id + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->unique_id[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.node.ID.1.0 node_id + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_node_ID_1_0_serialize_( + &obj->node_id, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_Entry_1_0_deserialize_( + uavcan_pnp_cluster_Entry_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 term + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint8[16] unique_id + for (size_t _index1_ = 0U; _index1_ < 16UL; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->unique_id[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->unique_id[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.node.ID.1.0 node_id + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err4_ = uavcan_node_ID_1_0_deserialize_( + &out_obj->node_id, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_cluster_Entry_1_0_initialize_(uavcan_pnp_cluster_Entry_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_cluster_Entry_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_ENTRY_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/pnp/cluster/RequestVote_1_0.h b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/RequestVote_1_0.h new file mode 100644 index 0000000..c2f09d5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/pnp/cluster/RequestVote_1_0.h @@ -0,0 +1,394 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.379080 UTC +// Is deprecated: no +// Fixed port-ID: 391 +// Full name: uavcan.pnp.cluster.RequestVote +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PNP_CLUSTER_REQUEST_VOTE_1_0_INCLUDED_ +#define UAVCAN_PNP_CLUSTER_REQUEST_VOTE_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_pnp_cluster_RequestVote_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_pnp_cluster_RequestVote_1_0_FIXED_PORT_ID_ 391U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.RequestVote.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_RequestVote_1_0_FULL_NAME_ "uavcan.pnp.cluster.RequestVote" +#define uavcan_pnp_cluster_RequestVote_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.RequestVote.1.0" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.RequestVote.Request.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_RequestVote_Request_1_0_FULL_NAME_ "uavcan.pnp.cluster.RequestVote.Request" +#define uavcan_pnp_cluster_RequestVote_Request_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.RequestVote.Request.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_cluster_RequestVote_Request_1_0_EXTENT_BYTES_ 48UL +#define uavcan_pnp_cluster_RequestVote_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 10UL +static_assert(uavcan_pnp_cluster_RequestVote_Request_1_0_EXTENT_BYTES_ >= uavcan_pnp_cluster_RequestVote_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint32 term + uint32_t term; + + /// saturated uint32 last_log_term + uint32_t last_log_term; + + /// saturated uint16 last_log_index + uint16_t last_log_index; +} uavcan_pnp_cluster_RequestVote_Request_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_cluster_RequestVote_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_RequestVote_Request_1_0_serialize_( + const uavcan_pnp_cluster_RequestVote_Request_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 80UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->term, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + { // saturated uint32 last_log_term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->last_log_term, 32U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + { // saturated uint16 last_log_index + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->last_log_index, 16U); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_RequestVote_Request_1_0_deserialize_( + uavcan_pnp_cluster_RequestVote_Request_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 term + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint32 last_log_term + out_obj->last_log_term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint16 last_log_index + out_obj->last_log_index = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_cluster_RequestVote_Request_1_0_initialize_(uavcan_pnp_cluster_RequestVote_Request_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_cluster_RequestVote_Request_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.pnp.cluster.RequestVote.Response.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_pnp_cluster_RequestVote_Response_1_0_FULL_NAME_ "uavcan.pnp.cluster.RequestVote.Response" +#define uavcan_pnp_cluster_RequestVote_Response_1_0_FULL_NAME_AND_VERSION_ "uavcan.pnp.cluster.RequestVote.Response.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_pnp_cluster_RequestVote_Response_1_0_EXTENT_BYTES_ 48UL +#define uavcan_pnp_cluster_RequestVote_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 5UL +static_assert(uavcan_pnp_cluster_RequestVote_Response_1_0_EXTENT_BYTES_ >= uavcan_pnp_cluster_RequestVote_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint32 term + uint32_t term; + + /// saturated bool vote_granted + bool vote_granted; +} uavcan_pnp_cluster_RequestVote_Response_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_pnp_cluster_RequestVote_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_RequestVote_Response_1_0_serialize_( + const uavcan_pnp_cluster_RequestVote_Response_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 40UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 term + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->term, 32U); + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += 32U; + } + { // saturated bool vote_granted + buffer[offset_bits / 8U] = obj->vote_granted ? 1U : 0U; + offset_bits += 1U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad1_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_pnp_cluster_RequestVote_Response_1_0_deserialize_( + uavcan_pnp_cluster_RequestVote_Response_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 term + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated bool vote_granted + if (offset_bits < capacity_bits) + { + out_obj->vote_granted = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->vote_granted = false; + } + offset_bits += 1U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_pnp_cluster_RequestVote_Response_1_0_initialize_(uavcan_pnp_cluster_RequestVote_Response_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_pnp_cluster_RequestVote_Response_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_REQUEST_VOTE_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/Empty_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/Empty_1_0.h new file mode 100644 index 0000000..c6ec83d --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/Empty_1_0.h @@ -0,0 +1,167 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Empty.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.531288 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.Empty +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_EMPTY_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_EMPTY_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Empty.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Empty.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Empty.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Empty.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Empty.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_Empty_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.Empty.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_Empty_1_0_FULL_NAME_ "uavcan.primitive.Empty" +#define uavcan_primitive_Empty_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.Empty.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_Empty_1_0_EXTENT_BYTES_ 0UL +#define uavcan_primitive_Empty_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(uavcan_primitive_Empty_1_0_EXTENT_BYTES_ >= uavcan_primitive_Empty_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_primitive_Empty_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_Empty_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_Empty_1_0_serialize_( + const uavcan_primitive_Empty_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_Empty_1_0_deserialize_( + uavcan_primitive_Empty_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_Empty_1_0_initialize_(uavcan_primitive_Empty_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_Empty_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_EMPTY_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/String_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/String_1_0.h new file mode 100644 index 0000000..6cf4fe0 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/String_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/String.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.533999 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.String +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_STRING_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_STRING_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/String.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/String.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/String.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/String.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/String.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_String_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.String.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_String_1_0_FULL_NAME_ "uavcan.primitive.String" +#define uavcan_primitive_String_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.String.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_String_1_0_EXTENT_BYTES_ 258UL +#define uavcan_primitive_String_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_primitive_String_1_0_EXTENT_BYTES_ >= uavcan_primitive_String_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=256] value +#define uavcan_primitive_String_1_0_value_ARRAY_CAPACITY_ 256U +#define uavcan_primitive_String_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=256] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + uint8_t elements[uavcan_primitive_String_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_String_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_String_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_String_1_0_serialize_( + const uavcan_primitive_String_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=256] value + if (obj->value.count > 256) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.count, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->value.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_String_1_0_deserialize_( + uavcan_primitive_String_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=256] value + // Array length prefix: truncated uint16 + out_obj->value.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->value.count > 256U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_String_1_0_initialize_(uavcan_primitive_String_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_String_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_STRING_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/Unstructured_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/Unstructured_1_0.h new file mode 100644 index 0000000..bf2110a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/Unstructured_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Unstructured.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.538071 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.Unstructured +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_UNSTRUCTURED_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_UNSTRUCTURED_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Unstructured.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Unstructured.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Unstructured.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Unstructured.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/Unstructured.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_Unstructured_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.Unstructured.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_Unstructured_1_0_FULL_NAME_ "uavcan.primitive.Unstructured" +#define uavcan_primitive_Unstructured_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.Unstructured.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_Unstructured_1_0_EXTENT_BYTES_ 258UL +#define uavcan_primitive_Unstructured_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_primitive_Unstructured_1_0_EXTENT_BYTES_ >= uavcan_primitive_Unstructured_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=256] value +#define uavcan_primitive_Unstructured_1_0_value_ARRAY_CAPACITY_ 256U +#define uavcan_primitive_Unstructured_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=256] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + uint8_t elements[uavcan_primitive_Unstructured_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_Unstructured_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_Unstructured_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_Unstructured_1_0_serialize_( + const uavcan_primitive_Unstructured_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=256] value + if (obj->value.count > 256) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.count, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->value.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_Unstructured_1_0_deserialize_( + uavcan_primitive_Unstructured_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=256] value + // Array length prefix: truncated uint16 + out_obj->value.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->value.count > 256U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_Unstructured_1_0_initialize_(uavcan_primitive_Unstructured_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_Unstructured_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_UNSTRUCTURED_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Bit_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Bit_1_0.h new file mode 100644 index 0000000..69b67e0 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Bit_1_0.h @@ -0,0 +1,227 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Bit.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.543707 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Bit +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_BIT_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_BIT_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Bit_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Bit.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Bit_1_0_FULL_NAME_ "uavcan.primitive.array.Bit" +#define uavcan_primitive_array_Bit_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Bit.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Bit_1_0_EXTENT_BYTES_ 258UL +#define uavcan_primitive_array_Bit_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_primitive_array_Bit_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Bit_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated bool[<=2048] value +#define uavcan_primitive_array_Bit_1_0_value_ARRAY_CAPACITY_ 2048U +#define uavcan_primitive_array_Bit_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated bool[<=2048] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + /// Bitpacked array, capacity 2048 bits. Access via @ref nunavutSetBit(), @ref nunavutGetBit(). + uint8_t bitpacked[256]; + size_t count; + } value; +} uavcan_primitive_array_Bit_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Bit_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Bit_1_0_serialize_( + const uavcan_primitive_array_Bit_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated bool[<=2048] value + if (obj->value.count > 2048) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.count, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + // Optimization prospect: this item is aligned at the byte boundary, so it is possible to use memmove(). + nunavutCopyBits(&buffer[0], offset_bits, obj->value.count, &obj->value.bitpacked[0], 0U); + offset_bits += obj->value.count; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Bit_1_0_deserialize_( + uavcan_primitive_array_Bit_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated bool[<=2048] value + // Array length prefix: truncated uint16 + out_obj->value.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->value.count > 2048U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + nunavutGetBits(&out_obj->value.bitpacked[0], &buffer[0], capacity_bytes, offset_bits, out_obj->value.count); + offset_bits += out_obj->value.count; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Bit_1_0_initialize_(uavcan_primitive_array_Bit_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Bit_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_BIT_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer16_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer16_1_0.h new file mode 100644 index 0000000..ac3c1be --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer16_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer16.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.552306 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_INTEGER16_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_INTEGER16_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Integer16_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Integer16.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Integer16_1_0_FULL_NAME_ "uavcan.primitive.array.Integer16" +#define uavcan_primitive_array_Integer16_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Integer16.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Integer16_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Integer16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Integer16_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Integer16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated int16[<=128] value +#define uavcan_primitive_array_Integer16_1_0_value_ARRAY_CAPACITY_ 128U +#define uavcan_primitive_array_Integer16_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated int16[<=128] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + int16_t elements[uavcan_primitive_array_Integer16_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Integer16_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Integer16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer16_1_0_serialize_( + const uavcan_primitive_array_Integer16_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int16[<=128] value + if (obj->value.count > 128) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_], 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer16_1_0_deserialize_( + uavcan_primitive_array_Integer16_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int16[<=128] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 128U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetI16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Integer16_1_0_initialize_(uavcan_primitive_array_Integer16_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Integer16_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER16_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer32_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer32_1_0.h new file mode 100644 index 0000000..af98546 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer32_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer32.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.561082 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_INTEGER32_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_INTEGER32_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Integer32_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Integer32.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Integer32_1_0_FULL_NAME_ "uavcan.primitive.array.Integer32" +#define uavcan_primitive_array_Integer32_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Integer32.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Integer32_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Integer32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Integer32_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Integer32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated int32[<=64] value +#define uavcan_primitive_array_Integer32_1_0_value_ARRAY_CAPACITY_ 64U +#define uavcan_primitive_array_Integer32_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated int32[<=64] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + int32_t elements[uavcan_primitive_array_Integer32_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Integer32_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Integer32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer32_1_0_serialize_( + const uavcan_primitive_array_Integer32_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int32[<=64] value + if (obj->value.count > 64) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_], 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer32_1_0_deserialize_( + uavcan_primitive_array_Integer32_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int32[<=64] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 64U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetI32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Integer32_1_0_initialize_(uavcan_primitive_array_Integer32_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Integer32_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER32_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer64_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer64_1_0.h new file mode 100644 index 0000000..69311dd --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer64_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer64.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.570331 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_INTEGER64_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_INTEGER64_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Integer64_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Integer64.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Integer64_1_0_FULL_NAME_ "uavcan.primitive.array.Integer64" +#define uavcan_primitive_array_Integer64_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Integer64.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Integer64_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Integer64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Integer64_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Integer64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated int64[<=32] value +#define uavcan_primitive_array_Integer64_1_0_value_ARRAY_CAPACITY_ 32U +#define uavcan_primitive_array_Integer64_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated int64[<=32] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + int64_t elements[uavcan_primitive_array_Integer64_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Integer64_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Integer64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer64_1_0_serialize_( + const uavcan_primitive_array_Integer64_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int64[<=32] value + if (obj->value.count > 32) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_], 64U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer64_1_0_deserialize_( + uavcan_primitive_array_Integer64_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int64[<=32] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 32U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetI64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Integer64_1_0_initialize_(uavcan_primitive_array_Integer64_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Integer64_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER64_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer8_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer8_1_0.h new file mode 100644 index 0000000..6184ad0 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Integer8_1_0.h @@ -0,0 +1,232 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer8.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.579130 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_INTEGER8_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_INTEGER8_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Integer8_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Integer8.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Integer8_1_0_FULL_NAME_ "uavcan.primitive.array.Integer8" +#define uavcan_primitive_array_Integer8_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Integer8.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Integer8_1_0_EXTENT_BYTES_ 258UL +#define uavcan_primitive_array_Integer8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_primitive_array_Integer8_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Integer8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated int8[<=256] value +#define uavcan_primitive_array_Integer8_1_0_value_ARRAY_CAPACITY_ 256U +#define uavcan_primitive_array_Integer8_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated int8[<=256] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + int8_t elements[uavcan_primitive_array_Integer8_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Integer8_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Integer8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer8_1_0_serialize_( + const uavcan_primitive_array_Integer8_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int8[<=256] value + if (obj->value.count > 256) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.count, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->value.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Integer8_1_0_deserialize_( + uavcan_primitive_array_Integer8_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int8[<=256] value + // Array length prefix: truncated uint16 + out_obj->value.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->value.count > 256U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetI8(&buffer[0], capacity_bytes, offset_bits, 8); + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Integer8_1_0_initialize_(uavcan_primitive_array_Integer8_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Integer8_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER8_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural16_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural16_1_0.h new file mode 100644 index 0000000..b72e94d --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural16_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural16.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.584327 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_NATURAL16_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_NATURAL16_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Natural16_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Natural16.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Natural16_1_0_FULL_NAME_ "uavcan.primitive.array.Natural16" +#define uavcan_primitive_array_Natural16_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Natural16.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Natural16_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Natural16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Natural16_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Natural16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint16[<=128] value +#define uavcan_primitive_array_Natural16_1_0_value_ARRAY_CAPACITY_ 128U +#define uavcan_primitive_array_Natural16_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint16[<=128] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + uint16_t elements[uavcan_primitive_array_Natural16_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Natural16_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Natural16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural16_1_0_serialize_( + const uavcan_primitive_array_Natural16_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16[<=128] value + if (obj->value.count > 128) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_], 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural16_1_0_deserialize_( + uavcan_primitive_array_Natural16_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16[<=128] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 128U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Natural16_1_0_initialize_(uavcan_primitive_array_Natural16_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Natural16_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL16_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural32_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural32_1_0.h new file mode 100644 index 0000000..16419bd --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural32_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural32.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.588500 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_NATURAL32_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_NATURAL32_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Natural32_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Natural32.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Natural32_1_0_FULL_NAME_ "uavcan.primitive.array.Natural32" +#define uavcan_primitive_array_Natural32_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Natural32.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Natural32_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Natural32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Natural32_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Natural32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint32[<=64] value +#define uavcan_primitive_array_Natural32_1_0_value_ARRAY_CAPACITY_ 64U +#define uavcan_primitive_array_Natural32_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint32[<=64] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + uint32_t elements[uavcan_primitive_array_Natural32_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Natural32_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Natural32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural32_1_0_serialize_( + const uavcan_primitive_array_Natural32_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32[<=64] value + if (obj->value.count > 64) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_], 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural32_1_0_deserialize_( + uavcan_primitive_array_Natural32_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32[<=64] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 64U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Natural32_1_0_initialize_(uavcan_primitive_array_Natural32_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Natural32_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL32_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural64_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural64_1_0.h new file mode 100644 index 0000000..a3ab7db --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural64_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural64.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.592724 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_NATURAL64_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_NATURAL64_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Natural64_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Natural64.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Natural64_1_0_FULL_NAME_ "uavcan.primitive.array.Natural64" +#define uavcan_primitive_array_Natural64_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Natural64.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Natural64_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Natural64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Natural64_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Natural64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint64[<=32] value +#define uavcan_primitive_array_Natural64_1_0_value_ARRAY_CAPACITY_ 32U +#define uavcan_primitive_array_Natural64_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint64[<=32] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + uint64_t elements[uavcan_primitive_array_Natural64_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Natural64_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Natural64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural64_1_0_serialize_( + const uavcan_primitive_array_Natural64_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint64[<=32] value + if (obj->value.count > 32) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_], 64U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural64_1_0_deserialize_( + uavcan_primitive_array_Natural64_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint64[<=32] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 32U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Natural64_1_0_initialize_(uavcan_primitive_array_Natural64_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Natural64_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL64_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural8_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural8_1_0.h new file mode 100644 index 0000000..93a13c2 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Natural8_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural8.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.597207 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_NATURAL8_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_NATURAL8_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Natural8_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Natural8.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Natural8_1_0_FULL_NAME_ "uavcan.primitive.array.Natural8" +#define uavcan_primitive_array_Natural8_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Natural8.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Natural8_1_0_EXTENT_BYTES_ 258UL +#define uavcan_primitive_array_Natural8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 258UL +static_assert(uavcan_primitive_array_Natural8_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Natural8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated uint8[<=256] value +#define uavcan_primitive_array_Natural8_1_0_value_ARRAY_CAPACITY_ 256U +#define uavcan_primitive_array_Natural8_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated uint8[<=256] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + uint8_t elements[uavcan_primitive_array_Natural8_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Natural8_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Natural8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural8_1_0_serialize_( + const uavcan_primitive_array_Natural8_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2064UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8[<=256] value + if (obj->value.count > 256) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint16 + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value.count, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->value.elements[_index0_]); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Natural8_1_0_deserialize_( + uavcan_primitive_array_Natural8_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8[<=256] value + // Array length prefix: truncated uint16 + out_obj->value.count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + if (out_obj->value.count > 256U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.elements[_index1_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.elements[_index1_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Natural8_1_0_initialize_(uavcan_primitive_array_Natural8_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Natural8_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL8_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Real16_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Real16_1_0.h new file mode 100644 index 0000000..37dd6ec --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Real16_1_0.h @@ -0,0 +1,249 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real16.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.602076 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Real16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_REAL16_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_REAL16_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Real16_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Real16.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Real16_1_0_FULL_NAME_ "uavcan.primitive.array.Real16" +#define uavcan_primitive_array_Real16_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Real16.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Real16_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Real16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Real16_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Real16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[<=128] value +#define uavcan_primitive_array_Real16_1_0_value_ARRAY_CAPACITY_ 128U +#define uavcan_primitive_array_Real16_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated float16[<=128] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + float elements[uavcan_primitive_array_Real16_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Real16_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Real16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Real16_1_0_serialize_( + const uavcan_primitive_array_Real16_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float16[<=128] value + if (obj->value.count > 128) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + float _sat0_ = obj->value.elements[_index0_]; + if (isfinite(_sat0_)) + { + if (_sat0_ < ((float) -65504.0)) + { + _sat0_ = ((float) -65504.0); + } + if (_sat0_ > ((float) 65504.0)) + { + _sat0_ = ((float) 65504.0); + } + } + const int8_t _err0_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Real16_1_0_deserialize_( + uavcan_primitive_array_Real16_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float16[<=128] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 128U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Real16_1_0_initialize_(uavcan_primitive_array_Real16_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Real16_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_REAL16_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Real32_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Real32_1_0.h new file mode 100644 index 0000000..6f37a5a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Real32_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real32.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.607063 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Real32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_REAL32_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_REAL32_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Real32_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Real32.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Real32_1_0_FULL_NAME_ "uavcan.primitive.array.Real32" +#define uavcan_primitive_array_Real32_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Real32.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Real32_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Real32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Real32_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Real32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[<=64] value +#define uavcan_primitive_array_Real32_1_0_value_ARRAY_CAPACITY_ 64U +#define uavcan_primitive_array_Real32_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated float32[<=64] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + float elements[uavcan_primitive_array_Real32_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Real32_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Real32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Real32_1_0_serialize_( + const uavcan_primitive_array_Real32_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[<=64] value + if (obj->value.count > 64) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Real32_1_0_deserialize_( + uavcan_primitive_array_Real32_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[<=64] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 64U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Real32_1_0_initialize_(uavcan_primitive_array_Real32_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Real32_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_REAL32_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/array/Real64_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/array/Real64_1_0.h new file mode 100644 index 0000000..355b24e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/array/Real64_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real64.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.612346 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Real64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_ARRAY_REAL64_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_ARRAY_REAL64_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/array/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_array_Real64_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.array.Real64.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_array_Real64_1_0_FULL_NAME_ "uavcan.primitive.array.Real64" +#define uavcan_primitive_array_Real64_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.array.Real64.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_array_Real64_1_0_EXTENT_BYTES_ 257UL +#define uavcan_primitive_array_Real64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 257UL +static_assert(uavcan_primitive_array_Real64_1_0_EXTENT_BYTES_ >= uavcan_primitive_array_Real64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float64[<=32] value +#define uavcan_primitive_array_Real64_1_0_value_ARRAY_CAPACITY_ 32U +#define uavcan_primitive_array_Real64_1_0_value_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// saturated float64[<=32] value + struct /// Array address equivalence guarantee: &elements[0] == &value + { + double elements[uavcan_primitive_array_Real64_1_0_value_ARRAY_CAPACITY_]; + size_t count; + } value; +} uavcan_primitive_array_Real64_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_array_Real64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Real64_1_0_serialize_( + const uavcan_primitive_array_Real64_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 2056UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float64[<=32] value + if (obj->value.count > 32) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->value.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->value.elements[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_array_Real64_1_0_deserialize_( + uavcan_primitive_array_Real64_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float64[<=32] value + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value.count = 0U; + } + offset_bits += 8U; + if (out_obj->value.count > 32U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + out_obj->value.elements[_index1_] = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_array_Real64_1_0_initialize_(uavcan_primitive_array_Real64_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_array_Real64_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_REAL64_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Bit_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Bit_1_0.h new file mode 100644 index 0000000..3548d76 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Bit_1_0.h @@ -0,0 +1,206 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Bit.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.617455 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Bit +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_BIT_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_BIT_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Bit.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Bit_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Bit.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Bit_1_0_FULL_NAME_ "uavcan.primitive.scalar.Bit" +#define uavcan_primitive_scalar_Bit_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Bit.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Bit_1_0_EXTENT_BYTES_ 1UL +#define uavcan_primitive_scalar_Bit_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_primitive_scalar_Bit_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Bit_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated bool value + bool value; +} uavcan_primitive_scalar_Bit_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Bit_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Bit_1_0_serialize_( + const uavcan_primitive_scalar_Bit_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated bool value + buffer[offset_bits / 8U] = obj->value ? 1U : 0U; + offset_bits += 1U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Bit_1_0_deserialize_( + uavcan_primitive_scalar_Bit_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated bool value + if (offset_bits < capacity_bits) + { + out_obj->value = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->value = false; + } + offset_bits += 1U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Bit_1_0_initialize_(uavcan_primitive_scalar_Bit_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Bit_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_BIT_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer16_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer16_1_0.h new file mode 100644 index 0000000..64bb2c0 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer16_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer16.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.621962 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_INTEGER16_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_INTEGER16_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Integer16_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Integer16.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Integer16_1_0_FULL_NAME_ "uavcan.primitive.scalar.Integer16" +#define uavcan_primitive_scalar_Integer16_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Integer16.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Integer16_1_0_EXTENT_BYTES_ 2UL +#define uavcan_primitive_scalar_Integer16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_primitive_scalar_Integer16_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Integer16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated int16 value + int16_t value; +} uavcan_primitive_scalar_Integer16_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Integer16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer16_1_0_serialize_( + const uavcan_primitive_scalar_Integer16_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int16 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer16_1_0_deserialize_( + uavcan_primitive_scalar_Integer16_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int16 value + out_obj->value = nunavutGetI16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Integer16_1_0_initialize_(uavcan_primitive_scalar_Integer16_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Integer16_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER16_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer32_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer32_1_0.h new file mode 100644 index 0000000..59ce7f6 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer32_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer32.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.628116 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_INTEGER32_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_INTEGER32_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Integer32_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Integer32.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Integer32_1_0_FULL_NAME_ "uavcan.primitive.scalar.Integer32" +#define uavcan_primitive_scalar_Integer32_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Integer32.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Integer32_1_0_EXTENT_BYTES_ 4UL +#define uavcan_primitive_scalar_Integer32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_primitive_scalar_Integer32_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Integer32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated int32 value + int32_t value; +} uavcan_primitive_scalar_Integer32_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Integer32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer32_1_0_serialize_( + const uavcan_primitive_scalar_Integer32_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int32 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer32_1_0_deserialize_( + uavcan_primitive_scalar_Integer32_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int32 value + out_obj->value = nunavutGetI32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Integer32_1_0_initialize_(uavcan_primitive_scalar_Integer32_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Integer32_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER32_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer64_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer64_1_0.h new file mode 100644 index 0000000..ad262fe --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer64_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer64.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.635254 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_INTEGER64_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_INTEGER64_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Integer64_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Integer64.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Integer64_1_0_FULL_NAME_ "uavcan.primitive.scalar.Integer64" +#define uavcan_primitive_scalar_Integer64_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Integer64.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Integer64_1_0_EXTENT_BYTES_ 8UL +#define uavcan_primitive_scalar_Integer64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(uavcan_primitive_scalar_Integer64_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Integer64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated int64 value + int64_t value; +} uavcan_primitive_scalar_Integer64_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Integer64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer64_1_0_serialize_( + const uavcan_primitive_scalar_Integer64_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 64UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int64 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 64U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer64_1_0_deserialize_( + uavcan_primitive_scalar_Integer64_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int64 value + out_obj->value = nunavutGetI64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Integer64_1_0_initialize_(uavcan_primitive_scalar_Integer64_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Integer64_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER64_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer8_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer8_1_0.h new file mode 100644 index 0000000..8e089b9 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Integer8_1_0.h @@ -0,0 +1,200 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer8.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.641094 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_INTEGER8_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_INTEGER8_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Integer8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Integer8_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Integer8.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Integer8_1_0_FULL_NAME_ "uavcan.primitive.scalar.Integer8" +#define uavcan_primitive_scalar_Integer8_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Integer8.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Integer8_1_0_EXTENT_BYTES_ 1UL +#define uavcan_primitive_scalar_Integer8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_primitive_scalar_Integer8_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Integer8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated int8 value + int8_t value; +} uavcan_primitive_scalar_Integer8_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Integer8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer8_1_0_serialize_( + const uavcan_primitive_scalar_Integer8_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated int8 value + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->value); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Integer8_1_0_deserialize_( + uavcan_primitive_scalar_Integer8_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated int8 value + out_obj->value = nunavutGetI8(&buffer[0], capacity_bytes, offset_bits, 8); + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Integer8_1_0_initialize_(uavcan_primitive_scalar_Integer8_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Integer8_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER8_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural16_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural16_1_0.h new file mode 100644 index 0000000..32ee391 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural16_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural16.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.647716 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_NATURAL16_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_NATURAL16_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Natural16_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Natural16.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Natural16_1_0_FULL_NAME_ "uavcan.primitive.scalar.Natural16" +#define uavcan_primitive_scalar_Natural16_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Natural16.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Natural16_1_0_EXTENT_BYTES_ 2UL +#define uavcan_primitive_scalar_Natural16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_primitive_scalar_Natural16_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Natural16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint16 value + uint16_t value; +} uavcan_primitive_scalar_Natural16_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Natural16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural16_1_0_serialize_( + const uavcan_primitive_scalar_Natural16_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint16 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 16U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural16_1_0_deserialize_( + uavcan_primitive_scalar_Natural16_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint16 value + out_obj->value = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Natural16_1_0_initialize_(uavcan_primitive_scalar_Natural16_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Natural16_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL16_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural32_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural32_1_0.h new file mode 100644 index 0000000..b2244b7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural32_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural32.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.654763 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_NATURAL32_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_NATURAL32_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Natural32_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Natural32.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Natural32_1_0_FULL_NAME_ "uavcan.primitive.scalar.Natural32" +#define uavcan_primitive_scalar_Natural32_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Natural32.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Natural32_1_0_EXTENT_BYTES_ 4UL +#define uavcan_primitive_scalar_Natural32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_primitive_scalar_Natural32_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Natural32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint32 value + uint32_t value; +} uavcan_primitive_scalar_Natural32_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Natural32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural32_1_0_serialize_( + const uavcan_primitive_scalar_Natural32_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint32 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 32U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural32_1_0_deserialize_( + uavcan_primitive_scalar_Natural32_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint32 value + out_obj->value = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Natural32_1_0_initialize_(uavcan_primitive_scalar_Natural32_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Natural32_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL32_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural64_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural64_1_0.h new file mode 100644 index 0000000..6d03231 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural64_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural64.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.663017 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_NATURAL64_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_NATURAL64_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Natural64_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Natural64.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Natural64_1_0_FULL_NAME_ "uavcan.primitive.scalar.Natural64" +#define uavcan_primitive_scalar_Natural64_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Natural64.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Natural64_1_0_EXTENT_BYTES_ 8UL +#define uavcan_primitive_scalar_Natural64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(uavcan_primitive_scalar_Natural64_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Natural64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint64 value + uint64_t value; +} uavcan_primitive_scalar_Natural64_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Natural64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural64_1_0_serialize_( + const uavcan_primitive_scalar_Natural64_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 64UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint64 value + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 64U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural64_1_0_deserialize_( + uavcan_primitive_scalar_Natural64_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint64 value + out_obj->value = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Natural64_1_0_initialize_(uavcan_primitive_scalar_Natural64_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Natural64_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL64_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural8_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural8_1_0.h new file mode 100644 index 0000000..3cf92d5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Natural8_1_0.h @@ -0,0 +1,207 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural8.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.669940 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_NATURAL8_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_NATURAL8_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Natural8.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Natural8_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Natural8.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Natural8_1_0_FULL_NAME_ "uavcan.primitive.scalar.Natural8" +#define uavcan_primitive_scalar_Natural8_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Natural8.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Natural8_1_0_EXTENT_BYTES_ 1UL +#define uavcan_primitive_scalar_Natural8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_primitive_scalar_Natural8_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Natural8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated uint8 value + uint8_t value; +} uavcan_primitive_scalar_Natural8_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Natural8_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural8_1_0_serialize_( + const uavcan_primitive_scalar_Natural8_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint8 value + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->value); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Natural8_1_0_deserialize_( + uavcan_primitive_scalar_Natural8_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint8 value + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->value = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->value = 0U; + } + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Natural8_1_0_initialize_(uavcan_primitive_scalar_Natural8_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Natural8_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL8_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real16_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real16_1_0.h new file mode 100644 index 0000000..a31f041 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real16_1_0.h @@ -0,0 +1,214 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real16.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.677852 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Real16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_REAL16_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_REAL16_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real16.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Real16_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Real16.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Real16_1_0_FULL_NAME_ "uavcan.primitive.scalar.Real16" +#define uavcan_primitive_scalar_Real16_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Real16.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Real16_1_0_EXTENT_BYTES_ 2UL +#define uavcan_primitive_scalar_Real16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_primitive_scalar_Real16_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Real16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float16 value + float value; +} uavcan_primitive_scalar_Real16_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Real16_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Real16_1_0_serialize_( + const uavcan_primitive_scalar_Real16_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float16 value + float _sat0_ = obj->value; + if (isfinite(_sat0_)) + { + if (_sat0_ < ((float) -65504.0)) + { + _sat0_ = ((float) -65504.0); + } + if (_sat0_ > ((float) 65504.0)) + { + _sat0_ = ((float) 65504.0); + } + } + const int8_t _err0_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 16U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Real16_1_0_deserialize_( + uavcan_primitive_scalar_Real16_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float16 value + out_obj->value = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Real16_1_0_initialize_(uavcan_primitive_scalar_Real16_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Real16_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_REAL16_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real32_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real32_1_0.h new file mode 100644 index 0000000..d020c69 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real32_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real32.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.685388 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Real32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_REAL32_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_REAL32_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real32.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Real32_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Real32.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Real32_1_0_FULL_NAME_ "uavcan.primitive.scalar.Real32" +#define uavcan_primitive_scalar_Real32_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Real32.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Real32_1_0_EXTENT_BYTES_ 4UL +#define uavcan_primitive_scalar_Real32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_primitive_scalar_Real32_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Real32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 value + float value; +} uavcan_primitive_scalar_Real32_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Real32_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Real32_1_0_serialize_( + const uavcan_primitive_scalar_Real32_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 value + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->value); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Real32_1_0_deserialize_( + uavcan_primitive_scalar_Real32_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 value + out_obj->value = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Real32_1_0_initialize_(uavcan_primitive_scalar_Real32_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Real32_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_REAL32_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real64_1_0.h b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real64_1_0.h new file mode 100644 index 0000000..03d5ca3 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/primitive/scalar/Real64_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real64.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.692798 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Real64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_PRIMITIVE_SCALAR_REAL64_1_0_INCLUDED_ +#define UAVCAN_PRIMITIVE_SCALAR_REAL64_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/primitive/scalar/Real64.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_primitive_scalar_Real64_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.primitive.scalar.Real64.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_primitive_scalar_Real64_1_0_FULL_NAME_ "uavcan.primitive.scalar.Real64" +#define uavcan_primitive_scalar_Real64_1_0_FULL_NAME_AND_VERSION_ "uavcan.primitive.scalar.Real64.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_primitive_scalar_Real64_1_0_EXTENT_BYTES_ 8UL +#define uavcan_primitive_scalar_Real64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(uavcan_primitive_scalar_Real64_1_0_EXTENT_BYTES_ >= uavcan_primitive_scalar_Real64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float64 value + double value; +} uavcan_primitive_scalar_Real64_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_primitive_scalar_Real64_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Real64_1_0_serialize_( + const uavcan_primitive_scalar_Real64_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 64UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float64 value + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->value); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_primitive_scalar_Real64_1_0_deserialize_( + uavcan_primitive_scalar_Real64_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float64 value + out_obj->value = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_primitive_scalar_Real64_1_0_initialize_(uavcan_primitive_scalar_Real64_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_primitive_scalar_Real64_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_REAL64_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Scalar_1_0.h new file mode 100644 index 0000000..25402f5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.765909 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.acceleration.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ACCELERATION_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ACCELERATION_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_acceleration_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.acceleration.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_acceleration_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.acceleration.Scalar" +#define uavcan_si_sample_acceleration_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.acceleration.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_acceleration_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_acceleration_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 meter_per_second_per_second + float meter_per_second_per_second; +} uavcan_si_sample_acceleration_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_acceleration_Scalar_1_0_serialize_( + const uavcan_si_sample_acceleration_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 meter_per_second_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second_per_second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_acceleration_Scalar_1_0_deserialize_( + uavcan_si_sample_acceleration_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 meter_per_second_per_second + out_obj->meter_per_second_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_acceleration_Scalar_1_0_initialize_(uavcan_si_sample_acceleration_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_acceleration_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Vector3_1_0.h new file mode 100644 index 0000000..ca6b875 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/acceleration/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.769982 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.acceleration.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ACCELERATION_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ACCELERATION_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_acceleration_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.acceleration.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_acceleration_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.acceleration.Vector3" +#define uavcan_si_sample_acceleration_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.acceleration.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_acceleration_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_acceleration_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] meter_per_second_per_second +#define uavcan_si_sample_acceleration_Vector3_1_0_meter_per_second_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_acceleration_Vector3_1_0_meter_per_second_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] meter_per_second_per_second + float meter_per_second_per_second[3]; +} uavcan_si_sample_acceleration_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_acceleration_Vector3_1_0_serialize_( + const uavcan_si_sample_acceleration_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] meter_per_second_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second_per_second[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_acceleration_Vector3_1_0_deserialize_( + uavcan_si_sample_acceleration_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] meter_per_second_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter_per_second_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_acceleration_Vector3_1_0_initialize_(uavcan_si_sample_acceleration_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_acceleration_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/angle/Quaternion_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/angle/Quaternion_1_0.h new file mode 100644 index 0000000..ddd2f76 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/angle/Quaternion_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Quaternion.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.743678 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.angle.Quaternion +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ANGLE_QUATERNION_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ANGLE_QUATERNION_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_angle_Quaternion_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.angle.Quaternion.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_angle_Quaternion_1_0_FULL_NAME_ "uavcan.si.sample.angle.Quaternion" +#define uavcan_si_sample_angle_Quaternion_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.angle.Quaternion.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_angle_Quaternion_1_0_EXTENT_BYTES_ 23UL +#define uavcan_si_sample_angle_Quaternion_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 23UL +static_assert(uavcan_si_sample_angle_Quaternion_1_0_EXTENT_BYTES_ >= uavcan_si_sample_angle_Quaternion_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[4] wxyz +#define uavcan_si_sample_angle_Quaternion_1_0_wxyz_ARRAY_CAPACITY_ 4U +#define uavcan_si_sample_angle_Quaternion_1_0_wxyz_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[4] wxyz + float wxyz[4]; +} uavcan_si_sample_angle_Quaternion_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_angle_Quaternion_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angle_Quaternion_1_0_serialize_( + const uavcan_si_sample_angle_Quaternion_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 184UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[4] wxyz + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 4UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->wxyz[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angle_Quaternion_1_0_deserialize_( + uavcan_si_sample_angle_Quaternion_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[4] wxyz + for (size_t _index1_ = 0U; _index1_ < 4UL; ++_index1_) + { + out_obj->wxyz[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_angle_Quaternion_1_0_initialize_(uavcan_si_sample_angle_Quaternion_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_angle_Quaternion_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGLE_QUATERNION_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/angle/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/angle/Scalar_1_0.h new file mode 100644 index 0000000..242465d --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/angle/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.748722 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.angle.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ANGLE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ANGLE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_angle_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.angle.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_angle_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.angle.Scalar" +#define uavcan_si_sample_angle_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.angle.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_angle_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_angle_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_angle_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_angle_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 radian + float radian; +} uavcan_si_sample_angle_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_angle_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angle_Scalar_1_0_serialize_( + const uavcan_si_sample_angle_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 radian + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angle_Scalar_1_0_deserialize_( + uavcan_si_sample_angle_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 radian + out_obj->radian = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_angle_Scalar_1_0_initialize_(uavcan_si_sample_angle_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_angle_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGLE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Scalar_1_0.h new file mode 100644 index 0000000..035b81d --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.697165 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.angular_acceleration.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_angular_acceleration_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.angular_acceleration.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_angular_acceleration_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.angular_acceleration.Scalar" +#define uavcan_si_sample_angular_acceleration_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.angular_acceleration.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_angular_acceleration_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_angular_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_angular_acceleration_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_angular_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 radian_per_second_per_second + float radian_per_second_per_second; +} uavcan_si_sample_angular_acceleration_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_angular_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_acceleration_Scalar_1_0_serialize_( + const uavcan_si_sample_angular_acceleration_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 radian_per_second_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second_per_second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_acceleration_Scalar_1_0_deserialize_( + uavcan_si_sample_angular_acceleration_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 radian_per_second_per_second + out_obj->radian_per_second_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_angular_acceleration_Scalar_1_0_initialize_(uavcan_si_sample_angular_acceleration_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_angular_acceleration_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Vector3_1_0.h new file mode 100644 index 0000000..b997f5e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_acceleration/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.702002 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.angular_acceleration.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.angular_acceleration.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.angular_acceleration.Vector3" +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.angular_acceleration.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_angular_acceleration_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_angular_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] radian_per_second_per_second +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_radian_per_second_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_angular_acceleration_Vector3_1_0_radian_per_second_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] radian_per_second_per_second + float radian_per_second_per_second[3]; +} uavcan_si_sample_angular_acceleration_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_angular_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_acceleration_Vector3_1_0_serialize_( + const uavcan_si_sample_angular_acceleration_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] radian_per_second_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second_per_second[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_acceleration_Vector3_1_0_deserialize_( + uavcan_si_sample_angular_acceleration_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] radian_per_second_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->radian_per_second_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_angular_acceleration_Vector3_1_0_initialize_(uavcan_si_sample_angular_acceleration_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_angular_acceleration_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Scalar_1_0.h new file mode 100644 index 0000000..8b45267 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.827534 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.angular_velocity.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_angular_velocity_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.angular_velocity.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_angular_velocity_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.angular_velocity.Scalar" +#define uavcan_si_sample_angular_velocity_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.angular_velocity.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_angular_velocity_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_angular_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_angular_velocity_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_angular_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 radian_per_second + float radian_per_second; +} uavcan_si_sample_angular_velocity_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_angular_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_velocity_Scalar_1_0_serialize_( + const uavcan_si_sample_angular_velocity_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 radian_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_velocity_Scalar_1_0_deserialize_( + uavcan_si_sample_angular_velocity_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 radian_per_second + out_obj->radian_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_angular_velocity_Scalar_1_0_initialize_(uavcan_si_sample_angular_velocity_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_angular_velocity_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Vector3_1_0.h new file mode 100644 index 0000000..7efe90b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/angular_velocity/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.833540 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.angular_velocity.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_angular_velocity_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.angular_velocity.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_angular_velocity_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.angular_velocity.Vector3" +#define uavcan_si_sample_angular_velocity_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.angular_velocity.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_angular_velocity_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_angular_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_angular_velocity_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_angular_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] radian_per_second +#define uavcan_si_sample_angular_velocity_Vector3_1_0_radian_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_angular_velocity_Vector3_1_0_radian_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] radian_per_second + float radian_per_second[3]; +} uavcan_si_sample_angular_velocity_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_angular_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_velocity_Vector3_1_0_serialize_( + const uavcan_si_sample_angular_velocity_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] radian_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_angular_velocity_Vector3_1_0_deserialize_( + uavcan_si_sample_angular_velocity_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] radian_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->radian_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_angular_velocity_Vector3_1_0_initialize_(uavcan_si_sample_angular_velocity_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_angular_velocity_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/duration/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/duration/Scalar_1_0.h new file mode 100644 index 0000000..4973af3 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/duration/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.864996 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.duration.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_DURATION_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_DURATION_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_duration_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.duration.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_duration_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.duration.Scalar" +#define uavcan_si_sample_duration_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.duration.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_duration_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_duration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_duration_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_duration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 second + float second; +} uavcan_si_sample_duration_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_duration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_duration_Scalar_1_0_serialize_( + const uavcan_si_sample_duration_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_duration_Scalar_1_0_deserialize_( + uavcan_si_sample_duration_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 second + out_obj->second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_duration_Scalar_1_0_initialize_(uavcan_si_sample_duration_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_duration_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_DURATION_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/duration/WideScalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/duration/WideScalar_1_0.h new file mode 100644 index 0000000..345b191 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/duration/WideScalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/WideScalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.869268 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.duration.WideScalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_DURATION_WIDE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_DURATION_WIDE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_duration_WideScalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.duration.WideScalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_duration_WideScalar_1_0_FULL_NAME_ "uavcan.si.sample.duration.WideScalar" +#define uavcan_si_sample_duration_WideScalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.duration.WideScalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_duration_WideScalar_1_0_EXTENT_BYTES_ 15UL +#define uavcan_si_sample_duration_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 15UL +static_assert(uavcan_si_sample_duration_WideScalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_duration_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float64 second + double second; +} uavcan_si_sample_duration_WideScalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_duration_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_duration_WideScalar_1_0_serialize_( + const uavcan_si_sample_duration_WideScalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 120UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float64 second + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_duration_WideScalar_1_0_deserialize_( + uavcan_si_sample_duration_WideScalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float64 second + out_obj->second = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_duration_WideScalar_1_0_initialize_(uavcan_si_sample_duration_WideScalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_duration_WideScalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_DURATION_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/electric_charge/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/electric_charge/Scalar_1_0.h new file mode 100644 index 0000000..267158f --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/electric_charge/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.707637 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.electric_charge.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_electric_charge_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.electric_charge.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_electric_charge_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.electric_charge.Scalar" +#define uavcan_si_sample_electric_charge_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.electric_charge.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_electric_charge_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_electric_charge_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_electric_charge_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_electric_charge_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 coulomb + float coulomb; +} uavcan_si_sample_electric_charge_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_electric_charge_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_electric_charge_Scalar_1_0_serialize_( + const uavcan_si_sample_electric_charge_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 coulomb + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->coulomb); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_electric_charge_Scalar_1_0_deserialize_( + uavcan_si_sample_electric_charge_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 coulomb + out_obj->coulomb = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_electric_charge_Scalar_1_0_initialize_(uavcan_si_sample_electric_charge_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_electric_charge_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/electric_current/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/electric_current/Scalar_1_0.h new file mode 100644 index 0000000..5d6d24a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/electric_current/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_current/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.806315 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.electric_current.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_electric_current_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.electric_current.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_electric_current_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.electric_current.Scalar" +#define uavcan_si_sample_electric_current_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.electric_current.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_electric_current_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_electric_current_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_electric_current_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_electric_current_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 ampere + float ampere; +} uavcan_si_sample_electric_current_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_electric_current_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_electric_current_Scalar_1_0_serialize_( + const uavcan_si_sample_electric_current_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 ampere + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->ampere); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_electric_current_Scalar_1_0_deserialize_( + uavcan_si_sample_electric_current_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 ampere + out_obj->ampere = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_electric_current_Scalar_1_0_initialize_(uavcan_si_sample_electric_current_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_electric_current_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/energy/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/energy/Scalar_1_0.h new file mode 100644 index 0000000..bd00ba5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/energy/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/energy/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.712563 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.energy.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_ENERGY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_ENERGY_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_energy_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.energy.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_energy_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.energy.Scalar" +#define uavcan_si_sample_energy_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.energy.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_energy_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_energy_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_energy_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_energy_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 joule + float joule; +} uavcan_si_sample_energy_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_energy_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_energy_Scalar_1_0_serialize_( + const uavcan_si_sample_energy_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 joule + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->joule); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_energy_Scalar_1_0_deserialize_( + uavcan_si_sample_energy_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 joule + out_obj->joule = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_energy_Scalar_1_0_initialize_(uavcan_si_sample_energy_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_energy_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ENERGY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/force/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/force/Scalar_1_0.h new file mode 100644 index 0000000..0585587 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/force/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.753047 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.force.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_FORCE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_FORCE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_force_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.force.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_force_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.force.Scalar" +#define uavcan_si_sample_force_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.force.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_force_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_force_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_force_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_force_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 newton + float newton; +} uavcan_si_sample_force_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_force_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_force_Scalar_1_0_serialize_( + const uavcan_si_sample_force_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 newton + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_force_Scalar_1_0_deserialize_( + uavcan_si_sample_force_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 newton + out_obj->newton = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_force_Scalar_1_0_initialize_(uavcan_si_sample_force_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_force_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_FORCE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/force/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/force/Vector3_1_0.h new file mode 100644 index 0000000..e5c0caa --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/force/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.757336 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.force.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_FORCE_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_FORCE_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_force_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.force.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_force_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.force.Vector3" +#define uavcan_si_sample_force_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.force.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_force_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_force_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_force_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_force_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] newton +#define uavcan_si_sample_force_Vector3_1_0_newton_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_force_Vector3_1_0_newton_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] newton + float newton[3]; +} uavcan_si_sample_force_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_force_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_force_Vector3_1_0_serialize_( + const uavcan_si_sample_force_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] newton + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_force_Vector3_1_0_deserialize_( + uavcan_si_sample_force_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] newton + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->newton[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_force_Vector3_1_0_initialize_(uavcan_si_sample_force_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_force_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_FORCE_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/frequency/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/frequency/Scalar_1_0.h new file mode 100644 index 0000000..16d23a7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/frequency/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/frequency/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.761820 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.frequency.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_FREQUENCY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_FREQUENCY_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_frequency_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.frequency.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_frequency_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.frequency.Scalar" +#define uavcan_si_sample_frequency_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.frequency.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_frequency_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_frequency_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_frequency_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_frequency_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 hertz + float hertz; +} uavcan_si_sample_frequency_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_frequency_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_frequency_Scalar_1_0_serialize_( + const uavcan_si_sample_frequency_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 hertz + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->hertz); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_frequency_Scalar_1_0_deserialize_( + uavcan_si_sample_frequency_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 hertz + out_obj->hertz = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_frequency_Scalar_1_0_initialize_(uavcan_si_sample_frequency_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_frequency_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_FREQUENCY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/length/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/length/Scalar_1_0.h new file mode 100644 index 0000000..57c0af8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/length/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.842784 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.length.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_LENGTH_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_LENGTH_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_length_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.length.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_length_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.length.Scalar" +#define uavcan_si_sample_length_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.length.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_length_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_length_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_length_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_length_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 meter + float meter; +} uavcan_si_sample_length_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_length_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_Scalar_1_0_serialize_( + const uavcan_si_sample_length_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_Scalar_1_0_deserialize_( + uavcan_si_sample_length_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 meter + out_obj->meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_length_Scalar_1_0_initialize_(uavcan_si_sample_length_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_length_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/length/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/length/Vector3_1_0.h new file mode 100644 index 0000000..8bb5a2c --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/length/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.847959 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.length.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_LENGTH_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_LENGTH_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_length_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.length.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_length_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.length.Vector3" +#define uavcan_si_sample_length_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.length.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_length_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_length_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_length_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_length_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] meter +#define uavcan_si_sample_length_Vector3_1_0_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_length_Vector3_1_0_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] meter + float meter[3]; +} uavcan_si_sample_length_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_length_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_Vector3_1_0_serialize_( + const uavcan_si_sample_length_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_Vector3_1_0_deserialize_( + uavcan_si_sample_length_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_length_Vector3_1_0_initialize_(uavcan_si_sample_length_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_length_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/length/WideScalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/length/WideScalar_1_0.h new file mode 100644 index 0000000..3af1dd7 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/length/WideScalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideScalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.852488 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.length.WideScalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_length_WideScalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.length.WideScalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_length_WideScalar_1_0_FULL_NAME_ "uavcan.si.sample.length.WideScalar" +#define uavcan_si_sample_length_WideScalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.length.WideScalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_length_WideScalar_1_0_EXTENT_BYTES_ 15UL +#define uavcan_si_sample_length_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 15UL +static_assert(uavcan_si_sample_length_WideScalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_length_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float64 meter + double meter; +} uavcan_si_sample_length_WideScalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_length_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_WideScalar_1_0_serialize_( + const uavcan_si_sample_length_WideScalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 120UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float64 meter + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->meter); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_WideScalar_1_0_deserialize_( + uavcan_si_sample_length_WideScalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float64 meter + out_obj->meter = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_length_WideScalar_1_0_initialize_(uavcan_si_sample_length_WideScalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_length_WideScalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/length/WideVector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/length/WideVector3_1_0.h new file mode 100644 index 0000000..f951d6c --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/length/WideVector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideVector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.856475 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.length.WideVector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_length_WideVector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.length.WideVector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_length_WideVector3_1_0_FULL_NAME_ "uavcan.si.sample.length.WideVector3" +#define uavcan_si_sample_length_WideVector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.length.WideVector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_length_WideVector3_1_0_EXTENT_BYTES_ 31UL +#define uavcan_si_sample_length_WideVector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 31UL +static_assert(uavcan_si_sample_length_WideVector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_length_WideVector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float64[3] meter +#define uavcan_si_sample_length_WideVector3_1_0_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_length_WideVector3_1_0_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float64[3] meter + double meter[3]; +} uavcan_si_sample_length_WideVector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_length_WideVector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_WideVector3_1_0_serialize_( + const uavcan_si_sample_length_WideVector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 248UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float64[3] meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->meter[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 64U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_length_WideVector3_1_0_deserialize_( + uavcan_si_sample_length_WideVector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float64[3] meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter[_index1_] = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_length_WideVector3_1_0_initialize_(uavcan_si_sample_length_WideVector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_length_WideVector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/luminance/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/luminance/Scalar_1_0.h new file mode 100644 index 0000000..174d272 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/luminance/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/luminance/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.838184 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.luminance.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_LUMINANCE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_LUMINANCE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_luminance_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.luminance.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_luminance_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.luminance.Scalar" +#define uavcan_si_sample_luminance_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.luminance.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_luminance_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_luminance_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_luminance_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_luminance_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 candela_per_square_meter + float candela_per_square_meter; +} uavcan_si_sample_luminance_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_luminance_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_luminance_Scalar_1_0_serialize_( + const uavcan_si_sample_luminance_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 candela_per_square_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->candela_per_square_meter); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_luminance_Scalar_1_0_deserialize_( + uavcan_si_sample_luminance_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 candela_per_square_meter + out_obj->candela_per_square_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_luminance_Scalar_1_0_initialize_(uavcan_si_sample_luminance_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_luminance_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LUMINANCE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h new file mode 100644 index 0000000..3c52cbf --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h @@ -0,0 +1,239 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.791951 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.si.sample.magnetic_field_strength.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.magnetic_field_strength.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.magnetic_field_strength.Scalar" +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.magnetic_field_strength.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_magnetic_field_strength_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_magnetic_field_strength_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 tesla + float tesla; +} uavcan_si_sample_magnetic_field_strength_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_magnetic_field_strength_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Scalar_1_0_serialize_( + const uavcan_si_sample_magnetic_field_strength_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 tesla + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Scalar_1_0_deserialize_( + uavcan_si_sample_magnetic_field_strength_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 tesla + out_obj->tesla = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_magnetic_field_strength_Scalar_1_0_initialize_(uavcan_si_sample_magnetic_field_strength_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_magnetic_field_strength_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.h b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.h new file mode 100644 index 0000000..d34f6d3 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.787829 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.magnetic_field_strength.Scalar +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.magnetic_field_strength.Scalar.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_1_FULL_NAME_ "uavcan.si.sample.magnetic_field_strength.Scalar" +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_1_FULL_NAME_AND_VERSION_ "uavcan.si.sample.magnetic_field_strength.Scalar.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_1_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_magnetic_field_strength_Scalar_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_magnetic_field_strength_Scalar_1_1_EXTENT_BYTES_ >= uavcan_si_sample_magnetic_field_strength_Scalar_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 ampere_per_meter + float ampere_per_meter; +} uavcan_si_sample_magnetic_field_strength_Scalar_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_magnetic_field_strength_Scalar_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Scalar_1_1_serialize_( + const uavcan_si_sample_magnetic_field_strength_Scalar_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 ampere_per_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->ampere_per_meter); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Scalar_1_1_deserialize_( + uavcan_si_sample_magnetic_field_strength_Scalar_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 ampere_per_meter + out_obj->ampere_per_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_magnetic_field_strength_Scalar_1_1_initialize_(uavcan_si_sample_magnetic_field_strength_Scalar_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_magnetic_field_strength_Scalar_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h new file mode 100644 index 0000000..1b4f614 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h @@ -0,0 +1,253 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.801596 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.si.sample.magnetic_field_strength.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.magnetic_field_strength.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.magnetic_field_strength.Vector3" +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.magnetic_field_strength.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_magnetic_field_strength_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_magnetic_field_strength_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] tesla +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_tesla_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_0_tesla_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] tesla + float tesla[3]; +} uavcan_si_sample_magnetic_field_strength_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_magnetic_field_strength_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Vector3_1_0_serialize_( + const uavcan_si_sample_magnetic_field_strength_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] tesla + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Vector3_1_0_deserialize_( + uavcan_si_sample_magnetic_field_strength_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] tesla + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->tesla[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_magnetic_field_strength_Vector3_1_0_initialize_(uavcan_si_sample_magnetic_field_strength_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_magnetic_field_strength_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h new file mode 100644 index 0000000..edeebf8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.796612 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.magnetic_field_strength.Vector3 +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.magnetic_field_strength.Vector3.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_FULL_NAME_ "uavcan.si.sample.magnetic_field_strength.Vector3" +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_FULL_NAME_AND_VERSION_ "uavcan.si.sample.magnetic_field_strength.Vector3.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_magnetic_field_strength_Vector3_1_1_EXTENT_BYTES_ >= uavcan_si_sample_magnetic_field_strength_Vector3_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] ampere_per_meter +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_ampere_per_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_magnetic_field_strength_Vector3_1_1_ampere_per_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] ampere_per_meter + float ampere_per_meter[3]; +} uavcan_si_sample_magnetic_field_strength_Vector3_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_magnetic_field_strength_Vector3_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Vector3_1_1_serialize_( + const uavcan_si_sample_magnetic_field_strength_Vector3_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] ampere_per_meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->ampere_per_meter[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_field_strength_Vector3_1_1_deserialize_( + uavcan_si_sample_magnetic_field_strength_Vector3_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] ampere_per_meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->ampere_per_meter[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_magnetic_field_strength_Vector3_1_1_initialize_(uavcan_si_sample_magnetic_field_strength_Vector3_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_magnetic_field_strength_Vector3_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Scalar_1_0.h new file mode 100644 index 0000000..52470c5 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.818652 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.magnetic_flux_density.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_magnetic_flux_density_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.magnetic_flux_density.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_magnetic_flux_density_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.magnetic_flux_density.Scalar" +#define uavcan_si_sample_magnetic_flux_density_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.magnetic_flux_density.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_magnetic_flux_density_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_magnetic_flux_density_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_magnetic_flux_density_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_magnetic_flux_density_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 tesla + float tesla; +} uavcan_si_sample_magnetic_flux_density_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_magnetic_flux_density_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_flux_density_Scalar_1_0_serialize_( + const uavcan_si_sample_magnetic_flux_density_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 tesla + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_flux_density_Scalar_1_0_deserialize_( + uavcan_si_sample_magnetic_flux_density_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 tesla + out_obj->tesla = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_magnetic_flux_density_Scalar_1_0_initialize_(uavcan_si_sample_magnetic_flux_density_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_magnetic_flux_density_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h new file mode 100644 index 0000000..d5dff04 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.822644 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.magnetic_flux_density.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.magnetic_flux_density.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.magnetic_flux_density.Vector3" +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.magnetic_flux_density.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_magnetic_flux_density_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_magnetic_flux_density_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] tesla +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_tesla_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_magnetic_flux_density_Vector3_1_0_tesla_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] tesla + float tesla[3]; +} uavcan_si_sample_magnetic_flux_density_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_magnetic_flux_density_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_flux_density_Vector3_1_0_serialize_( + const uavcan_si_sample_magnetic_flux_density_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] tesla + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_magnetic_flux_density_Vector3_1_0_deserialize_( + uavcan_si_sample_magnetic_flux_density_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] tesla + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->tesla[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_magnetic_flux_density_Vector3_1_0_initialize_(uavcan_si_sample_magnetic_flux_density_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_magnetic_flux_density_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/mass/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/mass/Scalar_1_0.h new file mode 100644 index 0000000..f4d01a1 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/mass/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/mass/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.778878 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.mass.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_MASS_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_MASS_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_mass_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.mass.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_mass_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.mass.Scalar" +#define uavcan_si_sample_mass_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.mass.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_mass_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_mass_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_mass_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_mass_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 kilogram + float kilogram; +} uavcan_si_sample_mass_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_mass_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_mass_Scalar_1_0_serialize_( + const uavcan_si_sample_mass_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 kilogram + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->kilogram); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_mass_Scalar_1_0_deserialize_( + uavcan_si_sample_mass_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 kilogram + out_obj->kilogram = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_mass_Scalar_1_0_initialize_(uavcan_si_sample_mass_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_mass_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MASS_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/power/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/power/Scalar_1_0.h new file mode 100644 index 0000000..0f61a8a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/power/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/power/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.814591 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.power.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_POWER_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_POWER_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_power_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.power.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_power_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.power.Scalar" +#define uavcan_si_sample_power_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.power.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_power_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_power_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_power_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_power_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 watt + float watt; +} uavcan_si_sample_power_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_power_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_power_Scalar_1_0_serialize_( + const uavcan_si_sample_power_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 watt + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->watt); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_power_Scalar_1_0_deserialize_( + uavcan_si_sample_power_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 watt + out_obj->watt = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_power_Scalar_1_0_initialize_(uavcan_si_sample_power_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_power_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_POWER_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/pressure/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/pressure/Scalar_1_0.h new file mode 100644 index 0000000..5c4673c --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/pressure/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/pressure/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.810499 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.pressure.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_PRESSURE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_PRESSURE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_pressure_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.pressure.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_pressure_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.pressure.Scalar" +#define uavcan_si_sample_pressure_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.pressure.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_pressure_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_pressure_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_pressure_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_pressure_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 pascal + float pascal; +} uavcan_si_sample_pressure_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_pressure_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_pressure_Scalar_1_0_serialize_( + const uavcan_si_sample_pressure_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 pascal + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->pascal); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_pressure_Scalar_1_0_deserialize_( + uavcan_si_sample_pressure_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 pascal + out_obj->pascal = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_pressure_Scalar_1_0_initialize_(uavcan_si_sample_pressure_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_pressure_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_PRESSURE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/temperature/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/temperature/Scalar_1_0.h new file mode 100644 index 0000000..77c9f5b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/temperature/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/temperature/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.783738 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.temperature.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_TEMPERATURE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_TEMPERATURE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_temperature_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.temperature.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_temperature_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.temperature.Scalar" +#define uavcan_si_sample_temperature_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.temperature.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_temperature_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_temperature_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_temperature_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_temperature_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 kelvin + float kelvin; +} uavcan_si_sample_temperature_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_temperature_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_temperature_Scalar_1_0_serialize_( + const uavcan_si_sample_temperature_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 kelvin + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->kelvin); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_temperature_Scalar_1_0_deserialize_( + uavcan_si_sample_temperature_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 kelvin + out_obj->kelvin = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_temperature_Scalar_1_0_initialize_(uavcan_si_sample_temperature_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_temperature_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_TEMPERATURE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/torque/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/torque/Scalar_1_0.h new file mode 100644 index 0000000..c3b90bd --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/torque/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.717099 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.torque.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_TORQUE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_TORQUE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_torque_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.torque.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_torque_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.torque.Scalar" +#define uavcan_si_sample_torque_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.torque.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_torque_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_torque_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_torque_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_torque_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 newton_meter + float newton_meter; +} uavcan_si_sample_torque_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_torque_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_torque_Scalar_1_0_serialize_( + const uavcan_si_sample_torque_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 newton_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton_meter); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_torque_Scalar_1_0_deserialize_( + uavcan_si_sample_torque_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 newton_meter + out_obj->newton_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_torque_Scalar_1_0_initialize_(uavcan_si_sample_torque_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_torque_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_TORQUE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/torque/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/torque/Vector3_1_0.h new file mode 100644 index 0000000..003c557 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/torque/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.722923 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.torque.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_TORQUE_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_TORQUE_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_torque_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.torque.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_torque_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.torque.Vector3" +#define uavcan_si_sample_torque_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.torque.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_torque_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_torque_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_torque_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_torque_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] newton_meter +#define uavcan_si_sample_torque_Vector3_1_0_newton_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_torque_Vector3_1_0_newton_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] newton_meter + float newton_meter[3]; +} uavcan_si_sample_torque_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_torque_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_torque_Vector3_1_0_serialize_( + const uavcan_si_sample_torque_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] newton_meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton_meter[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_torque_Vector3_1_0_deserialize_( + uavcan_si_sample_torque_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] newton_meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->newton_meter[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_torque_Vector3_1_0_initialize_(uavcan_si_sample_torque_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_torque_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_TORQUE_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Scalar_1_0.h new file mode 100644 index 0000000..98917f2 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.733403 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.velocity.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_VELOCITY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_VELOCITY_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_velocity_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.velocity.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_velocity_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.velocity.Scalar" +#define uavcan_si_sample_velocity_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.velocity.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_velocity_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_velocity_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 meter_per_second + float meter_per_second; +} uavcan_si_sample_velocity_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_velocity_Scalar_1_0_serialize_( + const uavcan_si_sample_velocity_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 meter_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_velocity_Scalar_1_0_deserialize_( + uavcan_si_sample_velocity_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 meter_per_second + out_obj->meter_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_velocity_Scalar_1_0_initialize_(uavcan_si_sample_velocity_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_velocity_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Vector3_1_0.h new file mode 100644 index 0000000..611905b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/velocity/Vector3_1_0.h @@ -0,0 +1,244 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.738400 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.velocity.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_VELOCITY_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_VELOCITY_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_velocity_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.velocity.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_velocity_Vector3_1_0_FULL_NAME_ "uavcan.si.sample.velocity.Vector3" +#define uavcan_si_sample_velocity_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.velocity.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_velocity_Vector3_1_0_EXTENT_BYTES_ 19UL +#define uavcan_si_sample_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(uavcan_si_sample_velocity_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_sample_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] meter_per_second +#define uavcan_si_sample_velocity_Vector3_1_0_meter_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_sample_velocity_Vector3_1_0_meter_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32[3] meter_per_second + float meter_per_second[3]; +} uavcan_si_sample_velocity_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_velocity_Vector3_1_0_serialize_( + const uavcan_si_sample_velocity_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 152UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32[3] meter_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second[_index0_]); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_velocity_Vector3_1_0_deserialize_( + uavcan_si_sample_velocity_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32[3] meter_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_velocity_Vector3_1_0_initialize_(uavcan_si_sample_velocity_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_velocity_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/voltage/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/voltage/Scalar_1_0.h new file mode 100644 index 0000000..07714ca --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/voltage/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/voltage/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.728509 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.voltage.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_VOLTAGE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_VOLTAGE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_voltage_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.voltage.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_voltage_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.voltage.Scalar" +#define uavcan_si_sample_voltage_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.voltage.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_voltage_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_voltage_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_voltage_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_voltage_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 volt + float volt; +} uavcan_si_sample_voltage_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_voltage_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_voltage_Scalar_1_0_serialize_( + const uavcan_si_sample_voltage_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 volt + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->volt); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_voltage_Scalar_1_0_deserialize_( + uavcan_si_sample_voltage_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 volt + out_obj->volt = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_voltage_Scalar_1_0_initialize_(uavcan_si_sample_voltage_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_voltage_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VOLTAGE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/volume/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/volume/Scalar_1_0.h new file mode 100644 index 0000000..eb0c00a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/volume/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volume/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.774387 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.volume.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_VOLUME_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_VOLUME_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_volume_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.volume.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_volume_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.volume.Scalar" +#define uavcan_si_sample_volume_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.volume.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_volume_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_volume_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_volume_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_volume_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 cubic_meter + float cubic_meter; +} uavcan_si_sample_volume_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_volume_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_volume_Scalar_1_0_serialize_( + const uavcan_si_sample_volume_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 cubic_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->cubic_meter); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_volume_Scalar_1_0_deserialize_( + uavcan_si_sample_volume_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 cubic_meter + out_obj->cubic_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_volume_Scalar_1_0_initialize_(uavcan_si_sample_volume_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_volume_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VOLUME_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/sample/volumetric_flow_rate/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/sample/volumetric_flow_rate/Scalar_1_0.h new file mode 100644 index 0000000..ce106ce --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/sample/volumetric_flow_rate/Scalar_1_0.h @@ -0,0 +1,230 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.860894 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.sample.volumetric_flow_rate.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_SAMPLE_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_SAMPLE_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.sample.volumetric_flow_rate.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_FULL_NAME_ "uavcan.si.sample.volumetric_flow_rate.Scalar" +#define uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.sample.volumetric_flow_rate.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_EXTENT_BYTES_ 11UL +#define uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 11UL +static_assert(uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// saturated float32 cubic_meter_per_second + float cubic_meter_per_second; +} uavcan_si_sample_volumetric_flow_rate_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_serialize_( + const uavcan_si_sample_volumetric_flow_rate_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 88UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + int8_t _err0_ = uavcan_time_SynchronizedTimestamp_1_0_serialize_( + &obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err0_ < 0) + { + return _err0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + { // saturated float32 cubic_meter_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err1_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->cubic_meter_per_second); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_deserialize_( + uavcan_si_sample_volumetric_flow_rate_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // uavcan.time.SynchronizedTimestamp.1.0 timestamp + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err3_ = uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + &out_obj->timestamp, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float32 cubic_meter_per_second + out_obj->cubic_meter_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_initialize_(uavcan_si_sample_volumetric_flow_rate_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_sample_volumetric_flow_rate_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Scalar_1_0.h new file mode 100644 index 0000000..7ef3c6e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.880511 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.acceleration.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ACCELERATION_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ACCELERATION_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_acceleration_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.acceleration.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_acceleration_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.acceleration.Scalar" +#define uavcan_si_unit_acceleration_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.acceleration.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_acceleration_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_acceleration_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 meter_per_second_per_second + float meter_per_second_per_second; +} uavcan_si_unit_acceleration_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_acceleration_Scalar_1_0_serialize_( + const uavcan_si_unit_acceleration_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 meter_per_second_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second_per_second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_acceleration_Scalar_1_0_deserialize_( + uavcan_si_unit_acceleration_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 meter_per_second_per_second + out_obj->meter_per_second_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_acceleration_Scalar_1_0_initialize_(uavcan_si_unit_acceleration_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_acceleration_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Vector3_1_0.h new file mode 100644 index 0000000..3078f13 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/acceleration/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.883998 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.acceleration.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ACCELERATION_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ACCELERATION_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_acceleration_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.acceleration.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_acceleration_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.acceleration.Vector3" +#define uavcan_si_unit_acceleration_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.acceleration.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_acceleration_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_acceleration_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] meter_per_second_per_second +#define uavcan_si_unit_acceleration_Vector3_1_0_meter_per_second_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_acceleration_Vector3_1_0_meter_per_second_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] meter_per_second_per_second + float meter_per_second_per_second[3]; +} uavcan_si_unit_acceleration_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_acceleration_Vector3_1_0_serialize_( + const uavcan_si_unit_acceleration_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] meter_per_second_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second_per_second[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_acceleration_Vector3_1_0_deserialize_( + uavcan_si_unit_acceleration_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] meter_per_second_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter_per_second_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_acceleration_Vector3_1_0_initialize_(uavcan_si_unit_acceleration_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_acceleration_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/angle/Quaternion_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/angle/Quaternion_1_0.h new file mode 100644 index 0000000..eaa8eee --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/angle/Quaternion_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Quaternion.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.930239 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.angle.Quaternion +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ANGLE_QUATERNION_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ANGLE_QUATERNION_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Quaternion.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_angle_Quaternion_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.angle.Quaternion.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_angle_Quaternion_1_0_FULL_NAME_ "uavcan.si.unit.angle.Quaternion" +#define uavcan_si_unit_angle_Quaternion_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.angle.Quaternion.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_angle_Quaternion_1_0_EXTENT_BYTES_ 16UL +#define uavcan_si_unit_angle_Quaternion_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 16UL +static_assert(uavcan_si_unit_angle_Quaternion_1_0_EXTENT_BYTES_ >= uavcan_si_unit_angle_Quaternion_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[4] wxyz +#define uavcan_si_unit_angle_Quaternion_1_0_wxyz_ARRAY_CAPACITY_ 4U +#define uavcan_si_unit_angle_Quaternion_1_0_wxyz_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[4] wxyz + float wxyz[4]; +} uavcan_si_unit_angle_Quaternion_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_angle_Quaternion_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angle_Quaternion_1_0_serialize_( + const uavcan_si_unit_angle_Quaternion_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 128UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[4] wxyz + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 4UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->wxyz[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angle_Quaternion_1_0_deserialize_( + uavcan_si_unit_angle_Quaternion_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[4] wxyz + for (size_t _index1_ = 0U; _index1_ < 4UL; ++_index1_) + { + out_obj->wxyz[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_angle_Quaternion_1_0_initialize_(uavcan_si_unit_angle_Quaternion_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_angle_Quaternion_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGLE_QUATERNION_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/angle/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/angle/Scalar_1_0.h new file mode 100644 index 0000000..eb3f350 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/angle/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.934142 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.angle.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ANGLE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ANGLE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angle/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_angle_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.angle.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_angle_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.angle.Scalar" +#define uavcan_si_unit_angle_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.angle.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_angle_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_angle_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_angle_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_angle_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 radian + float radian; +} uavcan_si_unit_angle_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_angle_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angle_Scalar_1_0_serialize_( + const uavcan_si_unit_angle_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 radian + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angle_Scalar_1_0_deserialize_( + uavcan_si_unit_angle_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 radian + out_obj->radian = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_angle_Scalar_1_0_initialize_(uavcan_si_unit_angle_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_angle_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGLE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Scalar_1_0.h new file mode 100644 index 0000000..f6c84f1 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.873292 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.angular_acceleration.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_angular_acceleration_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.angular_acceleration.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_angular_acceleration_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.angular_acceleration.Scalar" +#define uavcan_si_unit_angular_acceleration_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.angular_acceleration.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_angular_acceleration_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_angular_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_angular_acceleration_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_angular_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 radian_per_second_per_second + float radian_per_second_per_second; +} uavcan_si_unit_angular_acceleration_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_angular_acceleration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_acceleration_Scalar_1_0_serialize_( + const uavcan_si_unit_angular_acceleration_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 radian_per_second_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second_per_second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_acceleration_Scalar_1_0_deserialize_( + uavcan_si_unit_angular_acceleration_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 radian_per_second_per_second + out_obj->radian_per_second_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_angular_acceleration_Scalar_1_0_initialize_(uavcan_si_unit_angular_acceleration_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_angular_acceleration_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Vector3_1_0.h new file mode 100644 index 0000000..d832cc1 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_acceleration/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.876708 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.angular_acceleration.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.angular_acceleration.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.angular_acceleration.Vector3" +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.angular_acceleration.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_angular_acceleration_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_angular_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] radian_per_second_per_second +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_radian_per_second_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_angular_acceleration_Vector3_1_0_radian_per_second_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] radian_per_second_per_second + float radian_per_second_per_second[3]; +} uavcan_si_unit_angular_acceleration_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_angular_acceleration_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_acceleration_Vector3_1_0_serialize_( + const uavcan_si_unit_angular_acceleration_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] radian_per_second_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second_per_second[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_acceleration_Vector3_1_0_deserialize_( + uavcan_si_unit_angular_acceleration_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] radian_per_second_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->radian_per_second_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_angular_acceleration_Vector3_1_0_initialize_(uavcan_si_unit_angular_acceleration_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_angular_acceleration_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Scalar_1_0.h new file mode 100644 index 0000000..6b1619f --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.995386 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.angular_velocity.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_angular_velocity_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.angular_velocity.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_angular_velocity_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.angular_velocity.Scalar" +#define uavcan_si_unit_angular_velocity_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.angular_velocity.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_angular_velocity_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_angular_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_angular_velocity_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_angular_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 radian_per_second + float radian_per_second; +} uavcan_si_unit_angular_velocity_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_angular_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_velocity_Scalar_1_0_serialize_( + const uavcan_si_unit_angular_velocity_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 radian_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_velocity_Scalar_1_0_deserialize_( + uavcan_si_unit_angular_velocity_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 radian_per_second + out_obj->radian_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_angular_velocity_Scalar_1_0_initialize_(uavcan_si_unit_angular_velocity_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_angular_velocity_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Vector3_1_0.h new file mode 100644 index 0000000..e9492eb --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/angular_velocity/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.998971 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.angular_velocity.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_angular_velocity_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.angular_velocity.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_angular_velocity_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.angular_velocity.Vector3" +#define uavcan_si_unit_angular_velocity_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.angular_velocity.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_angular_velocity_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_angular_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_angular_velocity_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_angular_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] radian_per_second +#define uavcan_si_unit_angular_velocity_Vector3_1_0_radian_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_angular_velocity_Vector3_1_0_radian_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] radian_per_second + float radian_per_second[3]; +} uavcan_si_unit_angular_velocity_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_angular_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_velocity_Vector3_1_0_serialize_( + const uavcan_si_unit_angular_velocity_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] radian_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->radian_per_second[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_angular_velocity_Vector3_1_0_deserialize_( + uavcan_si_unit_angular_velocity_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] radian_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->radian_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_angular_velocity_Vector3_1_0_initialize_(uavcan_si_unit_angular_velocity_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_angular_velocity_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/duration/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/duration/Scalar_1_0.h new file mode 100644 index 0000000..ea942f1 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/duration/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.918865 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.duration.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_DURATION_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_DURATION_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_duration_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.duration.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_duration_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.duration.Scalar" +#define uavcan_si_unit_duration_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.duration.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_duration_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_duration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_duration_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_duration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 second + float second; +} uavcan_si_unit_duration_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_duration_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_duration_Scalar_1_0_serialize_( + const uavcan_si_unit_duration_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_duration_Scalar_1_0_deserialize_( + uavcan_si_unit_duration_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 second + out_obj->second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_duration_Scalar_1_0_initialize_(uavcan_si_unit_duration_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_duration_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_DURATION_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/duration/WideScalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/duration/WideScalar_1_0.h new file mode 100644 index 0000000..6cefb67 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/duration/WideScalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/WideScalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.922847 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.duration.WideScalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_DURATION_WIDE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_DURATION_WIDE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/duration/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_duration_WideScalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.duration.WideScalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_duration_WideScalar_1_0_FULL_NAME_ "uavcan.si.unit.duration.WideScalar" +#define uavcan_si_unit_duration_WideScalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.duration.WideScalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_duration_WideScalar_1_0_EXTENT_BYTES_ 8UL +#define uavcan_si_unit_duration_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(uavcan_si_unit_duration_WideScalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_duration_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float64 second + double second; +} uavcan_si_unit_duration_WideScalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_duration_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_duration_WideScalar_1_0_serialize_( + const uavcan_si_unit_duration_WideScalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 64UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float64 second + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_duration_WideScalar_1_0_deserialize_( + uavcan_si_unit_duration_WideScalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float64 second + out_obj->second = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_duration_WideScalar_1_0_initialize_(uavcan_si_unit_duration_WideScalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_duration_WideScalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_DURATION_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/electric_charge/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/electric_charge/Scalar_1_0.h new file mode 100644 index 0000000..5b65704 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/electric_charge/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.991887 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.electric_charge.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_electric_charge_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.electric_charge.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_electric_charge_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.electric_charge.Scalar" +#define uavcan_si_unit_electric_charge_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.electric_charge.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_electric_charge_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_electric_charge_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_electric_charge_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_electric_charge_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 coulomb + float coulomb; +} uavcan_si_unit_electric_charge_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_electric_charge_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_electric_charge_Scalar_1_0_serialize_( + const uavcan_si_unit_electric_charge_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 coulomb + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->coulomb); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_electric_charge_Scalar_1_0_deserialize_( + uavcan_si_unit_electric_charge_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 coulomb + out_obj->coulomb = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_electric_charge_Scalar_1_0_initialize_(uavcan_si_unit_electric_charge_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_electric_charge_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/electric_current/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/electric_current/Scalar_1_0.h new file mode 100644 index 0000000..77f3b5b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/electric_current/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_current/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.926748 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.electric_current.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/electric_current/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_electric_current_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.electric_current.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_electric_current_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.electric_current.Scalar" +#define uavcan_si_unit_electric_current_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.electric_current.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_electric_current_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_electric_current_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_electric_current_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_electric_current_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 ampere + float ampere; +} uavcan_si_unit_electric_current_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_electric_current_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + const uavcan_si_unit_electric_current_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 ampere + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->ampere); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + uavcan_si_unit_electric_current_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 ampere + out_obj->ampere = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_electric_current_Scalar_1_0_initialize_(uavcan_si_unit_electric_current_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/energy/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/energy/Scalar_1_0.h new file mode 100644 index 0000000..5dc3708 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/energy/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/energy/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.911684 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.energy.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_ENERGY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_ENERGY_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/energy/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_energy_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.energy.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_energy_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.energy.Scalar" +#define uavcan_si_unit_energy_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.energy.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_energy_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_energy_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_energy_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_energy_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 joule + float joule; +} uavcan_si_unit_energy_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_energy_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_energy_Scalar_1_0_serialize_( + const uavcan_si_unit_energy_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 joule + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->joule); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_energy_Scalar_1_0_deserialize_( + uavcan_si_unit_energy_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 joule + out_obj->joule = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_energy_Scalar_1_0_initialize_(uavcan_si_unit_energy_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_energy_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ENERGY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/force/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/force/Scalar_1_0.h new file mode 100644 index 0000000..f8ee6ab --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/force/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.944427 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.force.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_FORCE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_FORCE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_force_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.force.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_force_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.force.Scalar" +#define uavcan_si_unit_force_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.force.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_force_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_force_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_force_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_force_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 newton + float newton; +} uavcan_si_unit_force_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_force_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_force_Scalar_1_0_serialize_( + const uavcan_si_unit_force_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 newton + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_force_Scalar_1_0_deserialize_( + uavcan_si_unit_force_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 newton + out_obj->newton = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_force_Scalar_1_0_initialize_(uavcan_si_unit_force_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_force_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_FORCE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/force/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/force/Vector3_1_0.h new file mode 100644 index 0000000..67d0c81 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/force/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.947924 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.force.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_FORCE_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_FORCE_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/force/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_force_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.force.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_force_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.force.Vector3" +#define uavcan_si_unit_force_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.force.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_force_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_force_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_force_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_force_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] newton +#define uavcan_si_unit_force_Vector3_1_0_newton_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_force_Vector3_1_0_newton_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] newton + float newton[3]; +} uavcan_si_unit_force_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_force_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_force_Vector3_1_0_serialize_( + const uavcan_si_unit_force_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] newton + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_force_Vector3_1_0_deserialize_( + uavcan_si_unit_force_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] newton + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->newton[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_force_Vector3_1_0_initialize_(uavcan_si_unit_force_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_force_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_FORCE_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/frequency/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/frequency/Scalar_1_0.h new file mode 100644 index 0000000..bc82033 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/frequency/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/frequency/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.915204 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.frequency.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_FREQUENCY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_FREQUENCY_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/frequency/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_frequency_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.frequency.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_frequency_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.frequency.Scalar" +#define uavcan_si_unit_frequency_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.frequency.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_frequency_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_frequency_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_frequency_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_frequency_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 hertz + float hertz; +} uavcan_si_unit_frequency_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_frequency_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_frequency_Scalar_1_0_serialize_( + const uavcan_si_unit_frequency_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 hertz + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->hertz); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_frequency_Scalar_1_0_deserialize_( + uavcan_si_unit_frequency_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 hertz + out_obj->hertz = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_frequency_Scalar_1_0_initialize_(uavcan_si_unit_frequency_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_frequency_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_FREQUENCY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/length/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/length/Scalar_1_0.h new file mode 100644 index 0000000..2022b9e --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/length/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.962912 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.length.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_LENGTH_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_LENGTH_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_length_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.length.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_length_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.length.Scalar" +#define uavcan_si_unit_length_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.length.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_length_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_length_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_length_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_length_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 meter + float meter; +} uavcan_si_unit_length_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_length_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_Scalar_1_0_serialize_( + const uavcan_si_unit_length_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_Scalar_1_0_deserialize_( + uavcan_si_unit_length_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 meter + out_obj->meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_length_Scalar_1_0_initialize_(uavcan_si_unit_length_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_length_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/length/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/length/Vector3_1_0.h new file mode 100644 index 0000000..72bd5ac --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/length/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.966392 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.length.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_LENGTH_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_LENGTH_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_length_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.length.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_length_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.length.Vector3" +#define uavcan_si_unit_length_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.length.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_length_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_length_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_length_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_length_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] meter +#define uavcan_si_unit_length_Vector3_1_0_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_length_Vector3_1_0_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] meter + float meter[3]; +} uavcan_si_unit_length_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_length_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_Vector3_1_0_serialize_( + const uavcan_si_unit_length_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_Vector3_1_0_deserialize_( + uavcan_si_unit_length_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_length_Vector3_1_0_initialize_(uavcan_si_unit_length_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_length_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/length/WideScalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/length/WideScalar_1_0.h new file mode 100644 index 0000000..7c1f243 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/length/WideScalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideScalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.970271 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.length.WideScalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideScalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_length_WideScalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.length.WideScalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_length_WideScalar_1_0_FULL_NAME_ "uavcan.si.unit.length.WideScalar" +#define uavcan_si_unit_length_WideScalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.length.WideScalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_length_WideScalar_1_0_EXTENT_BYTES_ 8UL +#define uavcan_si_unit_length_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(uavcan_si_unit_length_WideScalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_length_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float64 meter + double meter; +} uavcan_si_unit_length_WideScalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_length_WideScalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_WideScalar_1_0_serialize_( + const uavcan_si_unit_length_WideScalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 64UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float64 meter + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->meter); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_WideScalar_1_0_deserialize_( + uavcan_si_unit_length_WideScalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float64 meter + out_obj->meter = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_length_WideScalar_1_0_initialize_(uavcan_si_unit_length_WideScalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_length_WideScalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/length/WideVector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/length/WideVector3_1_0.h new file mode 100644 index 0000000..45e6202 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/length/WideVector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideVector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.973722 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.length.WideVector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/length/WideVector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_length_WideVector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.length.WideVector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_length_WideVector3_1_0_FULL_NAME_ "uavcan.si.unit.length.WideVector3" +#define uavcan_si_unit_length_WideVector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.length.WideVector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_length_WideVector3_1_0_EXTENT_BYTES_ 24UL +#define uavcan_si_unit_length_WideVector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 24UL +static_assert(uavcan_si_unit_length_WideVector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_length_WideVector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float64[3] meter +#define uavcan_si_unit_length_WideVector3_1_0_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_length_WideVector3_1_0_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float64[3] meter + double meter[3]; +} uavcan_si_unit_length_WideVector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_length_WideVector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_WideVector3_1_0_serialize_( + const uavcan_si_unit_length_WideVector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 192UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float64[3] meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float64 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_DOUBLE, "Native IEEE754 binary64 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF64(&buffer[0], capacity_bytes, offset_bits, obj->meter[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_length_WideVector3_1_0_deserialize_( + uavcan_si_unit_length_WideVector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float64[3] meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter[_index1_] = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_length_WideVector3_1_0_initialize_(uavcan_si_unit_length_WideVector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_length_WideVector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/luminance/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/luminance/Scalar_1_0.h new file mode 100644 index 0000000..49968eb --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/luminance/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/luminance/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.977558 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.luminance.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_LUMINANCE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_LUMINANCE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/luminance/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_luminance_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.luminance.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_luminance_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.luminance.Scalar" +#define uavcan_si_unit_luminance_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.luminance.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_luminance_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_luminance_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_luminance_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_luminance_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 candela_per_square_meter + float candela_per_square_meter; +} uavcan_si_unit_luminance_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_luminance_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_luminance_Scalar_1_0_serialize_( + const uavcan_si_unit_luminance_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 candela_per_square_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->candela_per_square_meter); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_luminance_Scalar_1_0_deserialize_( + uavcan_si_unit_luminance_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 candela_per_square_meter + out_obj->candela_per_square_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_luminance_Scalar_1_0_initialize_(uavcan_si_unit_luminance_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_luminance_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LUMINANCE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h new file mode 100644 index 0000000..64ae464 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h @@ -0,0 +1,213 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.892545 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.si.unit.magnetic_field_strength.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.magnetic_field_strength.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.magnetic_field_strength.Scalar" +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.magnetic_field_strength.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_magnetic_field_strength_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_magnetic_field_strength_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 tesla + float tesla; +} uavcan_si_unit_magnetic_field_strength_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_magnetic_field_strength_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Scalar_1_0_serialize_( + const uavcan_si_unit_magnetic_field_strength_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 tesla + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Scalar_1_0_deserialize_( + uavcan_si_unit_magnetic_field_strength_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 tesla + out_obj->tesla = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_magnetic_field_strength_Scalar_1_0_initialize_(uavcan_si_unit_magnetic_field_strength_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_magnetic_field_strength_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_1.h b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_1.h new file mode 100644 index 0000000..08f3a40 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Scalar_1_1.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.888021 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.magnetic_field_strength.Scalar +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ +#define UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.magnetic_field_strength.Scalar.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_1_FULL_NAME_ "uavcan.si.unit.magnetic_field_strength.Scalar" +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_1_FULL_NAME_AND_VERSION_ "uavcan.si.unit.magnetic_field_strength.Scalar.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_1_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_magnetic_field_strength_Scalar_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_magnetic_field_strength_Scalar_1_1_EXTENT_BYTES_ >= uavcan_si_unit_magnetic_field_strength_Scalar_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 ampere_per_meter + float ampere_per_meter; +} uavcan_si_unit_magnetic_field_strength_Scalar_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_magnetic_field_strength_Scalar_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Scalar_1_1_serialize_( + const uavcan_si_unit_magnetic_field_strength_Scalar_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 ampere_per_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->ampere_per_meter); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Scalar_1_1_deserialize_( + uavcan_si_unit_magnetic_field_strength_Scalar_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 ampere_per_meter + out_obj->ampere_per_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_magnetic_field_strength_Scalar_1_1_initialize_(uavcan_si_unit_magnetic_field_strength_Scalar_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_magnetic_field_strength_Scalar_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h new file mode 100644 index 0000000..7b8ca83 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h @@ -0,0 +1,227 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.900201 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.si.unit.magnetic_field_strength.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +// _____ ______ _____ _____ ______ _____ _______ ______ _____ +// | __ `| ____| __ `| __ `| ____/ ____| /`|__ __| ____| __ ` +// | | | | |__ | |__) | |__) | |__ | | / ` | | | |__ | | | | +// | | | | __| | ___/| _ /| __|| | / /` ` | | | __| | | | | +// | |__| | |____| | | | ` `| |___| |____ / ____ `| | | |____| |__| | +// |_____/|______|_| |_| `_`______`_____/_/ `_`_| |______|_____/ +// +// WARNING: this data type is deprecated and is nearing the end of its life cycle. Seek replacement. + +#ifndef UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.magnetic_field_strength.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.magnetic_field_strength.Vector3" +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.magnetic_field_strength.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_magnetic_field_strength_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_magnetic_field_strength_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] tesla +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_tesla_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_0_tesla_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] tesla + float tesla[3]; +} uavcan_si_unit_magnetic_field_strength_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_magnetic_field_strength_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Vector3_1_0_serialize_( + const uavcan_si_unit_magnetic_field_strength_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] tesla + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Vector3_1_0_deserialize_( + uavcan_si_unit_magnetic_field_strength_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] tesla + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->tesla[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_magnetic_field_strength_Vector3_1_0_initialize_(uavcan_si_unit_magnetic_field_strength_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_magnetic_field_strength_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_1.h b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_1.h new file mode 100644 index 0000000..4a1858a --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_field_strength/Vector3_1_1.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl +// Generated at: 2024-09-11 21:29:53.896300 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.magnetic_field_strength.Vector3 +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ +#define UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.magnetic_field_strength.Vector3.1.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_FULL_NAME_ "uavcan.si.unit.magnetic_field_strength.Vector3" +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_FULL_NAME_AND_VERSION_ "uavcan.si.unit.magnetic_field_strength.Vector3.1.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_magnetic_field_strength_Vector3_1_1_EXTENT_BYTES_ >= uavcan_si_unit_magnetic_field_strength_Vector3_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] ampere_per_meter +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_ampere_per_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_magnetic_field_strength_Vector3_1_1_ampere_per_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] ampere_per_meter + float ampere_per_meter[3]; +} uavcan_si_unit_magnetic_field_strength_Vector3_1_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_magnetic_field_strength_Vector3_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Vector3_1_1_serialize_( + const uavcan_si_unit_magnetic_field_strength_Vector3_1_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] ampere_per_meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->ampere_per_meter[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_field_strength_Vector3_1_1_deserialize_( + uavcan_si_unit_magnetic_field_strength_Vector3_1_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] ampere_per_meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->ampere_per_meter[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_magnetic_field_strength_Vector3_1_1_initialize_(uavcan_si_unit_magnetic_field_strength_Vector3_1_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_magnetic_field_strength_Vector3_1_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Scalar_1_0.h new file mode 100644 index 0000000..902df76 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.006386 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.magnetic_flux_density.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_magnetic_flux_density_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.magnetic_flux_density.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_magnetic_flux_density_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.magnetic_flux_density.Scalar" +#define uavcan_si_unit_magnetic_flux_density_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.magnetic_flux_density.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_magnetic_flux_density_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_magnetic_flux_density_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_magnetic_flux_density_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_magnetic_flux_density_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 tesla + float tesla; +} uavcan_si_unit_magnetic_flux_density_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_magnetic_flux_density_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_flux_density_Scalar_1_0_serialize_( + const uavcan_si_unit_magnetic_flux_density_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 tesla + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_flux_density_Scalar_1_0_deserialize_( + uavcan_si_unit_magnetic_flux_density_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 tesla + out_obj->tesla = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_magnetic_flux_density_Scalar_1_0_initialize_(uavcan_si_unit_magnetic_flux_density_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_magnetic_flux_density_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.h new file mode 100644 index 0000000..055f45f --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.009899 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.magnetic_flux_density.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.magnetic_flux_density.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.magnetic_flux_density.Vector3" +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.magnetic_flux_density.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_magnetic_flux_density_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_magnetic_flux_density_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] tesla +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_tesla_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_magnetic_flux_density_Vector3_1_0_tesla_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] tesla + float tesla[3]; +} uavcan_si_unit_magnetic_flux_density_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_magnetic_flux_density_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_flux_density_Vector3_1_0_serialize_( + const uavcan_si_unit_magnetic_flux_density_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] tesla + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->tesla[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_magnetic_flux_density_Vector3_1_0_deserialize_( + uavcan_si_unit_magnetic_flux_density_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] tesla + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->tesla[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_magnetic_flux_density_Vector3_1_0_initialize_(uavcan_si_unit_magnetic_flux_density_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_magnetic_flux_density_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/mass/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/mass/Scalar_1_0.h new file mode 100644 index 0000000..4959026 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/mass/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/mass/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:54.002904 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.mass.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_MASS_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_MASS_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/mass/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_mass_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.mass.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_mass_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.mass.Scalar" +#define uavcan_si_unit_mass_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.mass.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_mass_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_mass_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_mass_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_mass_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 kilogram + float kilogram; +} uavcan_si_unit_mass_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_mass_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_mass_Scalar_1_0_serialize_( + const uavcan_si_unit_mass_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 kilogram + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->kilogram); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_mass_Scalar_1_0_deserialize_( + uavcan_si_unit_mass_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 kilogram + out_obj->kilogram = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_mass_Scalar_1_0_initialize_(uavcan_si_unit_mass_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_mass_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MASS_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/power/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/power/Scalar_1_0.h new file mode 100644 index 0000000..bf753d1 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/power/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/power/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.908095 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.power.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_POWER_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_POWER_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/power/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_power_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.power.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_power_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.power.Scalar" +#define uavcan_si_unit_power_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.power.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_power_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_power_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_power_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_power_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 watt + float watt; +} uavcan_si_unit_power_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_power_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_power_Scalar_1_0_serialize_( + const uavcan_si_unit_power_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 watt + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->watt); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_power_Scalar_1_0_deserialize_( + uavcan_si_unit_power_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 watt + out_obj->watt = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_power_Scalar_1_0_initialize_(uavcan_si_unit_power_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_power_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_POWER_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/pressure/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/pressure/Scalar_1_0.h new file mode 100644 index 0000000..a5e5922 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/pressure/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/pressure/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.951897 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.pressure.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_PRESSURE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_PRESSURE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/pressure/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_pressure_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.pressure.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_pressure_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.pressure.Scalar" +#define uavcan_si_unit_pressure_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.pressure.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_pressure_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_pressure_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_pressure_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_pressure_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 pascal + float pascal; +} uavcan_si_unit_pressure_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_pressure_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_pressure_Scalar_1_0_serialize_( + const uavcan_si_unit_pressure_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 pascal + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->pascal); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_pressure_Scalar_1_0_deserialize_( + uavcan_si_unit_pressure_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 pascal + out_obj->pascal = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_pressure_Scalar_1_0_initialize_(uavcan_si_unit_pressure_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_pressure_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_PRESSURE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/temperature/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/temperature/Scalar_1_0.h new file mode 100644 index 0000000..919abcb --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/temperature/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/temperature/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.937583 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.temperature.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_TEMPERATURE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_TEMPERATURE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/temperature/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_temperature_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.temperature.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_temperature_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.temperature.Scalar" +#define uavcan_si_unit_temperature_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.temperature.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_temperature_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_temperature_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_temperature_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_temperature_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 kelvin + float kelvin; +} uavcan_si_unit_temperature_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_temperature_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_temperature_Scalar_1_0_serialize_( + const uavcan_si_unit_temperature_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 kelvin + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->kelvin); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_temperature_Scalar_1_0_deserialize_( + uavcan_si_unit_temperature_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 kelvin + out_obj->kelvin = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_temperature_Scalar_1_0_initialize_(uavcan_si_unit_temperature_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_temperature_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_TEMPERATURE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/torque/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/torque/Scalar_1_0.h new file mode 100644 index 0000000..e4d8113 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/torque/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.984608 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.torque.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_TORQUE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_TORQUE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_torque_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.torque.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_torque_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.torque.Scalar" +#define uavcan_si_unit_torque_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.torque.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_torque_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_torque_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_torque_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_torque_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 newton_meter + float newton_meter; +} uavcan_si_unit_torque_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_torque_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_torque_Scalar_1_0_serialize_( + const uavcan_si_unit_torque_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 newton_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton_meter); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_torque_Scalar_1_0_deserialize_( + uavcan_si_unit_torque_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 newton_meter + out_obj->newton_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_torque_Scalar_1_0_initialize_(uavcan_si_unit_torque_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_torque_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_TORQUE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/torque/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/torque/Vector3_1_0.h new file mode 100644 index 0000000..55be0d8 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/torque/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.988045 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.torque.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_TORQUE_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_TORQUE_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/torque/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_torque_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.torque.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_torque_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.torque.Vector3" +#define uavcan_si_unit_torque_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.torque.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_torque_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_torque_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_torque_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_torque_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] newton_meter +#define uavcan_si_unit_torque_Vector3_1_0_newton_meter_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_torque_Vector3_1_0_newton_meter_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] newton_meter + float newton_meter[3]; +} uavcan_si_unit_torque_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_torque_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_torque_Vector3_1_0_serialize_( + const uavcan_si_unit_torque_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] newton_meter + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->newton_meter[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_torque_Vector3_1_0_deserialize_( + uavcan_si_unit_torque_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] newton_meter + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->newton_meter[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_torque_Vector3_1_0_initialize_(uavcan_si_unit_torque_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_torque_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_TORQUE_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Scalar_1_0.h new file mode 100644 index 0000000..3746387 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.955380 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.velocity.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_VELOCITY_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_VELOCITY_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_velocity_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.velocity.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_velocity_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.velocity.Scalar" +#define uavcan_si_unit_velocity_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.velocity.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_velocity_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_velocity_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 meter_per_second + float meter_per_second; +} uavcan_si_unit_velocity_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_velocity_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_velocity_Scalar_1_0_serialize_( + const uavcan_si_unit_velocity_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 meter_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_velocity_Scalar_1_0_deserialize_( + uavcan_si_unit_velocity_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 meter_per_second + out_obj->meter_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_velocity_Scalar_1_0_initialize_(uavcan_si_unit_velocity_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_velocity_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Vector3_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Vector3_1_0.h new file mode 100644 index 0000000..da6b1fd --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/velocity/Vector3_1_0.h @@ -0,0 +1,218 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Vector3.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.959027 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.velocity.Vector3 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_VELOCITY_VECTOR3_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_VELOCITY_VECTOR3_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/velocity/Vector3.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_velocity_Vector3_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.velocity.Vector3.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_velocity_Vector3_1_0_FULL_NAME_ "uavcan.si.unit.velocity.Vector3" +#define uavcan_si_unit_velocity_Vector3_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.velocity.Vector3.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_velocity_Vector3_1_0_EXTENT_BYTES_ 12UL +#define uavcan_si_unit_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(uavcan_si_unit_velocity_Vector3_1_0_EXTENT_BYTES_ >= uavcan_si_unit_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float32[3] meter_per_second +#define uavcan_si_unit_velocity_Vector3_1_0_meter_per_second_ARRAY_CAPACITY_ 3U +#define uavcan_si_unit_velocity_Vector3_1_0_meter_per_second_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float32[3] meter_per_second + float meter_per_second[3]; +} uavcan_si_unit_velocity_Vector3_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_velocity_Vector3_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_velocity_Vector3_1_0_serialize_( + const uavcan_si_unit_velocity_Vector3_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 96UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32[3] meter_per_second + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->meter_per_second[_index0_]); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_velocity_Vector3_1_0_deserialize_( + uavcan_si_unit_velocity_Vector3_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32[3] meter_per_second + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + out_obj->meter_per_second[_index1_] = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_velocity_Vector3_1_0_initialize_(uavcan_si_unit_velocity_Vector3_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_velocity_Vector3_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/voltage/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/voltage/Scalar_1_0.h new file mode 100644 index 0000000..c9ed6a4 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/voltage/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/voltage/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.981175 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.voltage.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_VOLTAGE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_VOLTAGE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/voltage/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_voltage_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.voltage.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_voltage_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.voltage.Scalar" +#define uavcan_si_unit_voltage_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.voltage.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_voltage_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_voltage_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_voltage_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_voltage_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 volt + float volt; +} uavcan_si_unit_voltage_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_voltage_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_voltage_Scalar_1_0_serialize_( + const uavcan_si_unit_voltage_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 volt + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->volt); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_voltage_Scalar_1_0_deserialize_( + uavcan_si_unit_voltage_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 volt + out_obj->volt = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_voltage_Scalar_1_0_initialize_(uavcan_si_unit_voltage_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_voltage_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VOLTAGE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/volume/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/volume/Scalar_1_0.h new file mode 100644 index 0000000..b171539 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/volume/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volume/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.941006 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.volume.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_VOLUME_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_VOLUME_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volume/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_volume_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.volume.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_volume_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.volume.Scalar" +#define uavcan_si_unit_volume_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.volume.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_volume_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_volume_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_volume_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_volume_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 cubic_meter + float cubic_meter; +} uavcan_si_unit_volume_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_volume_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_volume_Scalar_1_0_serialize_( + const uavcan_si_unit_volume_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 cubic_meter + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->cubic_meter); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_volume_Scalar_1_0_deserialize_( + uavcan_si_unit_volume_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 cubic_meter + out_obj->cubic_meter = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_volume_Scalar_1_0_initialize_(uavcan_si_unit_volume_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_volume_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VOLUME_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/si/unit/volumetric_flow_rate/Scalar_1_0.h b/components/esp_nunavut/nunavut/uavcan/si/unit/volumetric_flow_rate/Scalar_1_0.h new file mode 100644 index 0000000..8232da4 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/si/unit/volumetric_flow_rate/Scalar_1_0.h @@ -0,0 +1,204 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.904229 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.si.unit.volumetric_flow_rate.Scalar +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_SI_UNIT_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ +#define UAVCAN_SI_UNIT_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.si.unit.volumetric_flow_rate.Scalar.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_FULL_NAME_ "uavcan.si.unit.volumetric_flow_rate.Scalar" +#define uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_FULL_NAME_AND_VERSION_ "uavcan.si.unit.volumetric_flow_rate.Scalar.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_EXTENT_BYTES_ 4UL +#define uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_EXTENT_BYTES_ >= uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 cubic_meter_per_second + float cubic_meter_per_second; +} uavcan_si_unit_volumetric_flow_rate_Scalar_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_serialize_( + const uavcan_si_unit_volumetric_flow_rate_Scalar_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 32UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 cubic_meter_per_second + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->cubic_meter_per_second); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_deserialize_( + uavcan_si_unit_volumetric_flow_rate_Scalar_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 cubic_meter_per_second + out_obj->cubic_meter_per_second = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_initialize_(uavcan_si_unit_volumetric_flow_rate_Scalar_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_si_unit_volumetric_flow_rate_Scalar_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/time/GetSynchronizationMasterInfo_0_1.h b/components/esp_nunavut/nunavut/uavcan/time/GetSynchronizationMasterInfo_0_1.h new file mode 100644 index 0000000..ad84833 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/time/GetSynchronizationMasterInfo_0_1.h @@ -0,0 +1,384 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.328610 UTC +// Is deprecated: no +// Fixed port-ID: 510 +// Full name: uavcan.time.GetSynchronizationMasterInfo +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_TIME_GET_SYNCHRONIZATION_MASTER_INFO_0_1_INCLUDED_ +#define UAVCAN_TIME_GET_SYNCHRONIZATION_MASTER_INFO_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_time_GetSynchronizationMasterInfo_0_1_HAS_FIXED_PORT_ID_ true +#define uavcan_time_GetSynchronizationMasterInfo_0_1_FIXED_PORT_ID_ 510U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.GetSynchronizationMasterInfo.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_GetSynchronizationMasterInfo_0_1_FULL_NAME_ "uavcan.time.GetSynchronizationMasterInfo" +#define uavcan_time_GetSynchronizationMasterInfo_0_1_FULL_NAME_AND_VERSION_ "uavcan.time.GetSynchronizationMasterInfo.0.1" + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.GetSynchronizationMasterInfo.Request.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_GetSynchronizationMasterInfo_Request_0_1_FULL_NAME_ "uavcan.time.GetSynchronizationMasterInfo.Request" +#define uavcan_time_GetSynchronizationMasterInfo_Request_0_1_FULL_NAME_AND_VERSION_ "uavcan.time.GetSynchronizationMasterInfo.Request.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_time_GetSynchronizationMasterInfo_Request_0_1_EXTENT_BYTES_ 48UL +#define uavcan_time_GetSynchronizationMasterInfo_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(uavcan_time_GetSynchronizationMasterInfo_Request_0_1_EXTENT_BYTES_ >= uavcan_time_GetSynchronizationMasterInfo_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} uavcan_time_GetSynchronizationMasterInfo_Request_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_time_GetSynchronizationMasterInfo_Request_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_GetSynchronizationMasterInfo_Request_0_1_serialize_( + const uavcan_time_GetSynchronizationMasterInfo_Request_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_GetSynchronizationMasterInfo_Request_0_1_deserialize_( + uavcan_time_GetSynchronizationMasterInfo_Request_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + *inout_buffer_size_bytes = 0U; + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_time_GetSynchronizationMasterInfo_Request_0_1_initialize_(uavcan_time_GetSynchronizationMasterInfo_Request_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_time_GetSynchronizationMasterInfo_Request_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.GetSynchronizationMasterInfo.Response.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_GetSynchronizationMasterInfo_Response_0_1_FULL_NAME_ "uavcan.time.GetSynchronizationMasterInfo.Response" +#define uavcan_time_GetSynchronizationMasterInfo_Response_0_1_FULL_NAME_AND_VERSION_ "uavcan.time.GetSynchronizationMasterInfo.Response.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_time_GetSynchronizationMasterInfo_Response_0_1_EXTENT_BYTES_ 192UL +#define uavcan_time_GetSynchronizationMasterInfo_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 7UL +static_assert(uavcan_time_GetSynchronizationMasterInfo_Response_0_1_EXTENT_BYTES_ >= uavcan_time_GetSynchronizationMasterInfo_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float32 error_variance + float error_variance; + + /// uavcan.time.TimeSystem.0.1 time_system + uavcan_time_TimeSystem_0_1 time_system; + + /// uavcan.time.TAIInfo.0.1 tai_info + uavcan_time_TAIInfo_0_1 tai_info; +} uavcan_time_GetSynchronizationMasterInfo_Response_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_time_GetSynchronizationMasterInfo_Response_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_GetSynchronizationMasterInfo_Response_0_1_serialize_( + const uavcan_time_GetSynchronizationMasterInfo_Response_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 56UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated float32 error_variance + // Saturation code not emitted -- assume the native representation of float32 is conformant. + static_assert(NUNAVUT_PLATFORM_IEEE754_FLOAT, "Native IEEE754 binary32 required. TODO: relax constraint"); + const int8_t _err0_ = nunavutSetF32(&buffer[0], capacity_bytes, offset_bits, obj->error_variance); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + { // uavcan.time.TimeSystem.0.1 time_system + size_t _size_bytes0_ = 1UL; // Nested object (max) size, in bytes. + int8_t _err2_ = uavcan_time_TimeSystem_0_1_serialize_( + &obj->time_system, &buffer[offset_bits / 8U], &_size_bytes0_); + if (_err2_ < 0) + { + return _err2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + } + { // uavcan.time.TAIInfo.0.1 tai_info + size_t _size_bytes1_ = 2UL; // Nested object (max) size, in bytes. + int8_t _err4_ = uavcan_time_TAIInfo_0_1_serialize_( + &obj->tai_info, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err4_ < 0) + { + return _err4_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_GetSynchronizationMasterInfo_Response_0_1_deserialize_( + uavcan_time_GetSynchronizationMasterInfo_Response_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated float32 error_variance + out_obj->error_variance = nunavutGetF32(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.time.TimeSystem.0.1 time_system + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err6_ = uavcan_time_TimeSystem_0_1_deserialize_( + &out_obj->time_system, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.time.TAIInfo.0.1 tai_info + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + const int8_t _err7_ = uavcan_time_TAIInfo_0_1_deserialize_( + &out_obj->tai_info, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_time_GetSynchronizationMasterInfo_Response_0_1_initialize_(uavcan_time_GetSynchronizationMasterInfo_Response_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_time_GetSynchronizationMasterInfo_Response_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_GET_SYNCHRONIZATION_MASTER_INFO_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/time/Synchronization_1_0.h b/components/esp_nunavut/nunavut/uavcan/time/Synchronization_1_0.h new file mode 100644 index 0000000..c3feedc --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/time/Synchronization_1_0.h @@ -0,0 +1,209 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/7168.Synchronization.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.335204 UTC +// Is deprecated: no +// Fixed port-ID: 7168 +// Full name: uavcan.time.Synchronization +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_TIME_SYNCHRONIZATION_1_0_INCLUDED_ +#define UAVCAN_TIME_SYNCHRONIZATION_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/7168.Synchronization.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/7168.Synchronization.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/7168.Synchronization.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/7168.Synchronization.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/7168.Synchronization.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +#define uavcan_time_Synchronization_1_0_HAS_FIXED_PORT_ID_ true +#define uavcan_time_Synchronization_1_0_FIXED_PORT_ID_ 7168U + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.Synchronization.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_Synchronization_1_0_FULL_NAME_ "uavcan.time.Synchronization" +#define uavcan_time_Synchronization_1_0_FULL_NAME_AND_VERSION_ "uavcan.time.Synchronization.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_time_Synchronization_1_0_EXTENT_BYTES_ 7UL +#define uavcan_time_Synchronization_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 7UL +static_assert(uavcan_time_Synchronization_1_0_EXTENT_BYTES_ >= uavcan_time_Synchronization_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_PUBLICATION_PERIOD = 1 +#define uavcan_time_Synchronization_1_0_MAX_PUBLICATION_PERIOD (1U) + +/// saturated uint8 PUBLISHER_TIMEOUT_PERIOD_MULTIPLIER = 3 +#define uavcan_time_Synchronization_1_0_PUBLISHER_TIMEOUT_PERIOD_MULTIPLIER (3U) + +typedef struct +{ + /// truncated uint56 previous_transmission_timestamp_microsecond + uint64_t previous_transmission_timestamp_microsecond; +} uavcan_time_Synchronization_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_time_Synchronization_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_Synchronization_1_0_serialize_( + const uavcan_time_Synchronization_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 56UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint56 previous_transmission_timestamp_microsecond + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->previous_transmission_timestamp_microsecond, 56U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 56U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_Synchronization_1_0_deserialize_( + uavcan_time_Synchronization_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint56 previous_transmission_timestamp_microsecond + out_obj->previous_transmission_timestamp_microsecond = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 56); + offset_bits += 56U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_time_Synchronization_1_0_initialize_(uavcan_time_Synchronization_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_time_Synchronization_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_SYNCHRONIZATION_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/time/SynchronizedTimestamp_1_0.h b/components/esp_nunavut/nunavut/uavcan/time/SynchronizedTimestamp_1_0.h new file mode 100644 index 0000000..d92431d --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/time/SynchronizedTimestamp_1_0.h @@ -0,0 +1,206 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/SynchronizedTimestamp.1.0.dsdl +// Generated at: 2024-09-11 21:29:53.338816 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.time.SynchronizedTimestamp +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_TIME_SYNCHRONIZED_TIMESTAMP_1_0_INCLUDED_ +#define UAVCAN_TIME_SYNCHRONIZED_TIMESTAMP_1_0_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/SynchronizedTimestamp.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/SynchronizedTimestamp.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/SynchronizedTimestamp.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/SynchronizedTimestamp.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/SynchronizedTimestamp.1.0.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_time_SynchronizedTimestamp_1_0_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.SynchronizedTimestamp.1.0 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_SynchronizedTimestamp_1_0_FULL_NAME_ "uavcan.time.SynchronizedTimestamp" +#define uavcan_time_SynchronizedTimestamp_1_0_FULL_NAME_AND_VERSION_ "uavcan.time.SynchronizedTimestamp.1.0" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_time_SynchronizedTimestamp_1_0_EXTENT_BYTES_ 7UL +#define uavcan_time_SynchronizedTimestamp_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 7UL +static_assert(uavcan_time_SynchronizedTimestamp_1_0_EXTENT_BYTES_ >= uavcan_time_SynchronizedTimestamp_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint56 UNKNOWN = 0 +#define uavcan_time_SynchronizedTimestamp_1_0_UNKNOWN (0ULL) + +typedef struct +{ + /// truncated uint56 microsecond + uint64_t microsecond; +} uavcan_time_SynchronizedTimestamp_1_0; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_time_SynchronizedTimestamp_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_SynchronizedTimestamp_1_0_serialize_( + const uavcan_time_SynchronizedTimestamp_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 56UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint56 microsecond + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->microsecond, 56U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 56U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_SynchronizedTimestamp_1_0_deserialize_( + uavcan_time_SynchronizedTimestamp_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint56 microsecond + out_obj->microsecond = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 56); + offset_bits += 56U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_time_SynchronizedTimestamp_1_0_initialize_(uavcan_time_SynchronizedTimestamp_1_0* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_time_SynchronizedTimestamp_1_0_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_SYNCHRONIZED_TIMESTAMP_1_0_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/time/TAIInfo_0_1.h b/components/esp_nunavut/nunavut/uavcan/time/TAIInfo_0_1.h new file mode 100644 index 0000000..c4a9826 --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/time/TAIInfo_0_1.h @@ -0,0 +1,214 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TAIInfo.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.342463 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.time.TAIInfo +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_TIME_TAI_INFO_0_1_INCLUDED_ +#define UAVCAN_TIME_TAI_INFO_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TAIInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TAIInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TAIInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TAIInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TAIInfo.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_time_TAIInfo_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.TAIInfo.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_TAIInfo_0_1_FULL_NAME_ "uavcan.time.TAIInfo" +#define uavcan_time_TAIInfo_0_1_FULL_NAME_AND_VERSION_ "uavcan.time.TAIInfo.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_time_TAIInfo_0_1_EXTENT_BYTES_ 2UL +#define uavcan_time_TAIInfo_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(uavcan_time_TAIInfo_0_1_EXTENT_BYTES_ >= uavcan_time_TAIInfo_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 DIFFERENCE_TAI_MINUS_GPS = 19 +#define uavcan_time_TAIInfo_0_1_DIFFERENCE_TAI_MINUS_GPS (19U) + +/// saturated uint10 DIFFERENCE_TAI_MINUS_UTC_UNKNOWN = 0 +#define uavcan_time_TAIInfo_0_1_DIFFERENCE_TAI_MINUS_UTC_UNKNOWN (0U) + +typedef struct +{ + /// saturated uint10 difference_tai_minus_utc + uint16_t difference_tai_minus_utc; +} uavcan_time_TAIInfo_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_time_TAIInfo_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_TAIInfo_0_1_serialize_( + const uavcan_time_TAIInfo_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 16UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // saturated uint10 difference_tai_minus_utc + uint16_t _sat0_ = obj->difference_tai_minus_utc; + if (_sat0_ > 1023U) + { + _sat0_ = 1023U; + } + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _sat0_, 10U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 10U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_TAIInfo_0_1_deserialize_( + uavcan_time_TAIInfo_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // saturated uint10 difference_tai_minus_utc + out_obj->difference_tai_minus_utc = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 10); + offset_bits += 10U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_time_TAIInfo_0_1_initialize_(uavcan_time_TAIInfo_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_time_TAIInfo_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_TAI_INFO_0_1_INCLUDED_ diff --git a/components/esp_nunavut/nunavut/uavcan/time/TimeSystem_0_1.h b/components/esp_nunavut/nunavut/uavcan/time/TimeSystem_0_1.h new file mode 100644 index 0000000..f0bab7b --- /dev/null +++ b/components/esp_nunavut/nunavut/uavcan/time/TimeSystem_0_1.h @@ -0,0 +1,215 @@ +// This is an AUTO-GENERATED Cyphal DSDL data type implementation. Curious? See https://opencyphal.org. +// You shouldn't attempt to edit this file. +// +// Checking this file under version control is not recommended unless it is used as part of a high-SIL +// safety-critical codebase. The typical usage scenario is to generate it as part of the build process. +// +// To avoid conflicts with definitions given in the source DSDL file, all entities created by the code generator +// are named with an underscore at the end, like foo_bar_(). +// +// Generator: nunavut-2.3.1 (serialization was enabled) +// Source file: /home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TimeSystem.0.1.dsdl +// Generated at: 2024-09-11 21:29:53.346127 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.time.TimeSystem +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.9.19 +// python_release_level: final +// python_build: ('main', 'Jun 25 2024 17:03:42') +// python_compiler: GCC 12.2.0 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.1.0-25-amd64-x86_64-with-glibc2.36 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: False +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef UAVCAN_TIME_TIME_SYSTEM_0_1_INCLUDED_ +#define UAVCAN_TIME_TIME_SYSTEM_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TimeSystem.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_OMIT_FLOAT_SERIALIZATION_SUPPORT == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TimeSystem.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_SERIALIZATION_ASSERTS == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TimeSystem.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_ENABLE_OVERRIDE_VARIABLE_ARRAY_CAPACITY == 0, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TimeSystem.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_CAST_FORMAT == 2368206204, + "/home/marcin/Documents/esp32_socketcand_adapter/components/esp_nunavut/public_regulated_data_types-master/uavcan/time/TimeSystem.0.1.dsdl is trying to use a serialization library that was compiled with " + "different language options. This is dangerous and therefore not allowed." ); + +#ifdef __cplusplus +extern "C" { +#endif + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define uavcan_time_TimeSystem_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | uavcan.time.TimeSystem.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define uavcan_time_TimeSystem_0_1_FULL_NAME_ "uavcan.time.TimeSystem" +#define uavcan_time_TimeSystem_0_1_FULL_NAME_AND_VERSION_ "uavcan.time.TimeSystem.0.1" + +/// Extent is the minimum amount of memory required to hold any serialized representation of any compatible +/// version of the data type; or, on other words, it is the the maximum possible size of received objects of this type. +/// The size is specified in bytes (rather than bits) because by definition, extent is an integer number of bytes long. +/// When allocating a deserialization (RX) buffer for this data type, it should be at least extent bytes large. +/// When allocating a serialization (TX) buffer, it is safe to use the size of the largest serialized representation +/// instead of the extent because it provides a tighter bound of the object size; it is safe because the concrete type +/// is always known during serialization (unlike deserialization). If not sure, use extent everywhere. +#define uavcan_time_TimeSystem_0_1_EXTENT_BYTES_ 1UL +#define uavcan_time_TimeSystem_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(uavcan_time_TimeSystem_0_1_EXTENT_BYTES_ >= uavcan_time_TimeSystem_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint4 MONOTONIC_SINCE_BOOT = 0 +#define uavcan_time_TimeSystem_0_1_MONOTONIC_SINCE_BOOT (0U) + +/// saturated uint4 TAI = 1 +#define uavcan_time_TimeSystem_0_1_TAI (1U) + +/// saturated uint4 APPLICATION_SPECIFIC = 15 +#define uavcan_time_TimeSystem_0_1_APPLICATION_SPECIFIC (15U) + +typedef struct +{ + /// truncated uint4 value + uint8_t value; +} uavcan_time_TimeSystem_0_1; + +/// Serialize an instance into the provided buffer. +/// The lifetime of the resulting serialized representation is independent of the original instance. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original object where possible. +/// +/// @param obj The object to serialize. +/// +/// @param buffer The destination buffer. There are no alignment requirements. +/// @see uavcan_time_TimeSystem_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the buffer in bytes. +/// Upon return this value will be updated with the size of the constructed serialized +/// representation (in bytes); this value is then to be passed over to the transport +/// layer. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_TimeSystem_0_1_serialize_( + const uavcan_time_TimeSystem_0_1* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes) +{ + if ((obj == NULL) || (buffer == NULL) || (inout_buffer_size_bytes == NULL)) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + if ((8U * (size_t) capacity_bytes) < 8UL) + { + return -NUNAVUT_ERROR_SERIALIZATION_BUFFER_TOO_SMALL; + } + // Notice that fields that are not an integer number of bytes long may overrun the space allocated for them + // in the serialization buffer up to the next byte boundary. This is by design and is guaranteed to be safe. + size_t offset_bits = 0U; + { // truncated uint4 value + buffer[offset_bits / 8U] = (uint8_t)(obj->value); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 4U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + *inout_buffer_size_bytes = (size_t) (offset_bits / 8U); + return NUNAVUT_SUCCESS; +} + +/// Deserialize an instance from the provided buffer. +/// The lifetime of the resulting object is independent of the original buffer. +/// This method may be slow for large objects (e.g., images, point clouds, radar samples), so in a later revision +/// we may define a zero-copy alternative that keeps references to the original buffer where possible. +/// +/// @param obj The object to update from the provided serialized representation. +/// +/// @param buffer The source buffer containing the serialized representation. There are no alignment requirements. +/// If the buffer is shorter or longer than expected, it will be implicitly zero-extended or truncated, +/// respectively; see Specification for "implicit zero extension" and "implicit truncation" rules. +/// +/// @param inout_buffer_size_bytes When calling, this is a pointer to the size of the supplied serialized +/// representation, in bytes. Upon return this value will be updated with the +/// size of the consumed fragment of the serialized representation (in bytes), +/// which may be smaller due to the implicit truncation rule, but it is guaranteed +/// to never exceed the original buffer size even if the implicit zero extension rule +/// was activated. In case of error this value is undefined. +/// +/// @returns Negative on error, zero on success. +static inline int8_t uavcan_time_TimeSystem_0_1_deserialize_( + uavcan_time_TimeSystem_0_1* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes) +{ + if ((out_obj == NULL) || (inout_buffer_size_bytes == NULL) || ((buffer == NULL) && (0 != *inout_buffer_size_bytes))) + { + return -NUNAVUT_ERROR_INVALID_ARGUMENT; + } + if (buffer == NULL) + { + buffer = (const uint8_t*)""; + } + const size_t capacity_bytes = *inout_buffer_size_bytes; + const size_t capacity_bits = capacity_bytes * (size_t) 8U; + size_t offset_bits = 0U; + // truncated uint4 value + if ((offset_bits + 4U) <= capacity_bits) + { + out_obj->value = buffer[offset_bits / 8U] & 15U; + } + else + { + out_obj->value = 0U; + } + offset_bits += 4U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + return NUNAVUT_SUCCESS; +} + +/// Initialize an instance to default values. Does nothing if @param out_obj is NULL. +/// This function intentionally leaves inactive elements uninitialized; for example, members of a variable-length +/// array beyond its length are left uninitialized; aliased union memory that is not used by the first union field +/// is left uninitialized, etc. If full zero-initialization is desired, just use memset(&obj, 0, sizeof(obj)). +static inline void uavcan_time_TimeSystem_0_1_initialize_(uavcan_time_TimeSystem_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = uavcan_time_TimeSystem_0_1_deserialize_(out_obj, &buf, &size_bytes); + + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_TIME_SYSTEM_0_1_INCLUDED_ diff --git a/components/esp_nunavut/recompile_dsdl.sh b/components/esp_nunavut/recompile_dsdl.sh new file mode 100755 index 0000000..c912d8e --- /dev/null +++ b/components/esp_nunavut/recompile_dsdl.sh @@ -0,0 +1,31 @@ +#!/bin/bash + +# This script downloads the latest OpenCyphal public regulated data type DSDLs from GitHub +# and compiles them to C headers in the 'nunavut/' directory. + +# Run this script if you'd like to update the esp_nunavut component. + +set -e + +echo "Downloading public regulated DSDLs from GitHub." +wget https://github.com/OpenCyphal/public_regulated_data_types/archive/refs/heads/master.zip +unzip -qq -o master.zip +rm -f master.zip + +echo +echo "Installing nunavut in temporary Python virtual environment..." +python -m venv tmp_venv +tmp_venv/bin/pip install --upgrade pip +tmp_venv/bin/pip install nunavut + +echo +echo "Compiling DSDLs to C headers in 'nunavut/'." +rm -rf nunavut +mkdir -p nunavut +tmp_venv/bin/nnvg -O nunavut --target-language c public_regulated_data_types-master/uavcan +# tmp_venv/bin/nnvg -O nunavut --target-language c public_regulated_data_types-master/reg --lookup-dir public_regulated_data_types-master/uavcan + +rm -rf tmp_venv +rm -rf public_regulated_data_types-master +echo +echo "Success! The 'nunavut/' directory now contains the compiled C headers." diff --git a/components/esp_o1heap/CMakeLists.txt b/components/esp_o1heap/CMakeLists.txt new file mode 100644 index 0000000..8ae499b --- /dev/null +++ b/components/esp_o1heap/CMakeLists.txt @@ -0,0 +1,5 @@ +idf_component_register( + SRCS + "o1heap.c" + INCLUDE_DIRS "include" +) \ No newline at end of file diff --git a/components/esp_o1heap/include/o1heap.h b/components/esp_o1heap/include/o1heap.h new file mode 100644 index 0000000..fb776b4 --- /dev/null +++ b/components/esp_o1heap/include/o1heap.h @@ -0,0 +1,122 @@ +// Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated +// documentation files (the "Software"), to deal in the Software without restriction, including without limitation +// the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, +// and to permit persons to whom the Software is furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in all copies or substantial portions +// of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +// WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS +// OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR +// OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +// +// Copyright (c) 2020 Pavel Kirienko +// Authors: Pavel Kirienko +// +// READ THE DOCUMENTATION IN README.md. + +#ifndef O1HEAP_H_INCLUDED +#define O1HEAP_H_INCLUDED + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/// The semantic version number of this distribution. +#define O1HEAP_VERSION_MAJOR 2 + +/// The guaranteed alignment depends on the platform pointer width. +#define O1HEAP_ALIGNMENT (sizeof(void*) * 4U) + +/// The definition is private, so the user code can only operate on pointers. This is done to enforce encapsulation. +typedef struct O1HeapInstance O1HeapInstance; + +/// Runtime diagnostic information. This information can be used to facilitate runtime self-testing, +/// as required by certain safety-critical development guidelines. +/// If assertion checks are not disabled, the library will perform automatic runtime self-diagnostics that trigger +/// an assertion failure if a heap corruption is detected. +/// Health checks and validation can be done with o1heapDoInvariantsHold(). +typedef struct +{ + /// The total amount of memory available for serving allocation requests (heap size). + /// The maximum allocation size is (capacity - O1HEAP_ALIGNMENT). + /// This parameter does not include the overhead used up by O1HeapInstance and arena alignment. + /// This parameter is constant. + size_t capacity; + + /// The amount of memory that is currently allocated, including the per-fragment overhead and size alignment. + /// For example, if the application requested a fragment of size 1 byte, the value reported here may be 32 bytes. + size_t allocated; + + /// The maximum value of 'allocated' seen since initialization. This parameter is never decreased. + size_t peak_allocated; + + /// The largest amount of memory that the allocator has attempted to allocate (perhaps unsuccessfully) + /// since initialization (not including the rounding and the allocator's own per-fragment overhead, + /// so the total is larger). This parameter is never decreased. The initial value is zero. + size_t peak_request_size; + + /// The number of times an allocation request could not be completed due to the lack of memory or + /// excessive fragmentation. OOM stands for "out of memory". This parameter is never decreased. + uint64_t oom_count; +} O1HeapDiagnostics; + +/// The arena base pointer shall be aligned at O1HEAP_ALIGNMENT, otherwise NULL is returned. +/// +/// The total heap capacity cannot exceed approx. (SIZE_MAX/2). If the arena size allows for a larger heap, +/// the excess will be silently truncated away (no error). This is not a realistic use case because a typical +/// application is unlikely to be able to dedicate that much of the address space for the heap. +/// +/// The function initializes a new heap instance allocated in the provided arena, taking some of its space for its +/// own needs (normally about 40..600 bytes depending on the architecture, but this parameter is not characterized). +/// A pointer to the newly initialized instance is returned. +/// +/// If the provided space is insufficient, NULL is returned. +/// +/// An initialized instance does not hold any resources. Therefore, if the instance is no longer needed, +/// it can be discarded without any de-initialization procedures. +/// +/// The heap is not thread-safe; external synchronization may be required. +O1HeapInstance* o1heapInit(void* const base, const size_t size); + +/// The semantics follows malloc() with additional guarantees the full list of which is provided below. +/// +/// If the allocation request is served successfully, a pointer to the newly allocated memory fragment is returned. +/// The returned pointer is guaranteed to be aligned at O1HEAP_ALIGNMENT. +/// +/// If the allocation request cannot be served due to the lack of memory or its excessive fragmentation, +/// a NULL pointer is returned. +/// +/// The function is executed in constant time. +/// The allocated memory is NOT zero-filled (because zero-filling is a variable-complexity operation). +void* o1heapAllocate(O1HeapInstance* const handle, const size_t amount); + +/// The semantics follows free() with additional guarantees the full list of which is provided below. +/// +/// If the pointer does not point to a previously allocated block and is not NULL, the behavior is undefined. +/// Builds where assertion checks are enabled may trigger an assertion failure for some invalid inputs. +/// +/// The function is executed in constant time. +void o1heapFree(O1HeapInstance* const handle, void* const pointer); + +/// Performs a basic sanity check on the heap. +/// This function can be used as a weak but fast method of heap corruption detection. +/// If the handle pointer is NULL, the behavior is undefined. +/// The time complexity is constant. +/// The return value is truth if the heap looks valid, falsity otherwise. +bool o1heapDoInvariantsHold(const O1HeapInstance* const handle); + +/// Samples and returns a copy of the diagnostic information, see O1HeapDiagnostics. +/// This function merely copies the structure from an internal storage, so it is fast to return. +/// If the handle pointer is NULL, the behavior is undefined. +O1HeapDiagnostics o1heapGetDiagnostics(const O1HeapInstance* const handle); + +#ifdef __cplusplus +} +#endif +#endif // O1HEAP_H_INCLUDED diff --git a/components/esp_o1heap/o1heap.c b/components/esp_o1heap/o1heap.c new file mode 100644 index 0000000..61e6e39 --- /dev/null +++ b/components/esp_o1heap/o1heap.c @@ -0,0 +1,497 @@ +// Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated +// documentation files (the "Software"), to deal in the Software without restriction, including without limitation +// the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, +// and to permit persons to whom the Software is furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in all copies or substantial portions +// of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +// WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS +// OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR +// OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +// +// Copyright (c) 2020 Pavel Kirienko +// Authors: Pavel Kirienko + +#include "o1heap.h" +#include +#include + +// ---------------------------------------- BUILD CONFIGURATION OPTIONS ---------------------------------------- + +/// Define this macro to include build configuration header. This is an alternative to the -D compiler flag. +/// Usage example with CMake: "-DO1HEAP_CONFIG_HEADER=\"${CMAKE_CURRENT_SOURCE_DIR}/my_o1heap_config.h\"" +#ifdef O1HEAP_CONFIG_HEADER +# include O1HEAP_CONFIG_HEADER +#endif + +/// The assertion macro defaults to the standard assert(). +/// It can be overridden to manually suppress assertion checks or use a different error handling policy. +#ifndef O1HEAP_ASSERT +// Intentional violation of MISRA: the assertion check macro cannot be replaced with a function definition. +# define O1HEAP_ASSERT(x) assert(x) // NOSONAR +#endif + +/// Allow usage of compiler intrinsics for branch annotation and CLZ. +#ifndef O1HEAP_USE_INTRINSICS +# define O1HEAP_USE_INTRINSICS 1 +#endif + +/// Branch probability annotations are used to improve the worst case execution time (WCET). They are entirely optional. +#if O1HEAP_USE_INTRINSICS && !defined(O1HEAP_LIKELY) +# if defined(__GNUC__) || defined(__clang__) || defined(__CC_ARM) +// Intentional violation of MISRA: branch hinting macro cannot be replaced with a function definition. +# define O1HEAP_LIKELY(x) __builtin_expect((x), 1) // NOSONAR +# endif +#endif +#ifndef O1HEAP_LIKELY +# define O1HEAP_LIKELY(x) x +#endif + +/// This option is used for testing only. Do not use in production. +#ifndef O1HEAP_PRIVATE +# define O1HEAP_PRIVATE static inline +#endif + +/// Count leading zeros (CLZ) is used for fast computation of binary logarithm (which needs to be done very often). +/// Most of the modern processors (including the embedded ones) implement dedicated hardware support for fast CLZ +/// computation, which is available via compiler intrinsics. The default implementation will automatically use +/// the intrinsics for some of the compilers; for others it will default to the slow software emulation, +/// which can be overridden by the user via O1HEAP_CONFIG_HEADER. The library guarantees that the argument is positive. +#if O1HEAP_USE_INTRINSICS && !defined(O1HEAP_CLZ) +# if defined(__GNUC__) || defined(__clang__) || defined(__CC_ARM) +# define O1HEAP_CLZ __builtin_clzl +# endif +#endif +#ifndef O1HEAP_CLZ +O1HEAP_PRIVATE uint_fast8_t O1HEAP_CLZ(const size_t x) +{ + O1HEAP_ASSERT(x > 0); + size_t t = ((size_t) 1U) << ((sizeof(size_t) * CHAR_BIT) - 1U); + uint_fast8_t r = 0; + while ((x & t) == 0) + { + t >>= 1U; + r++; + } + return r; +} +#endif + +// ---------------------------------------- INTERNAL DEFINITIONS ---------------------------------------- + +#if !defined(__STDC_VERSION__) || (__STDC_VERSION__ < 199901L) +# error "Unsupported language: ISO C99 or a newer version is required." +#endif + +#if __STDC_VERSION__ < 201112L +// Intentional violation of MISRA: static assertion macro cannot be replaced with a function definition. +# define static_assert(x, ...) typedef char _static_assert_gl(_static_assertion_, __LINE__)[(x) ? 1 : -1] // NOSONAR +# define _static_assert_gl(a, b) _static_assert_gl_impl(a, b) // NOSONAR +// Intentional violation of MISRA: the paste operator ## cannot be avoided in this context. +# define _static_assert_gl_impl(a, b) a##b // NOSONAR +#endif + +/// The overhead is at most O1HEAP_ALIGNMENT bytes large, +/// then follows the user data which shall keep the next fragment aligned. +#define FRAGMENT_SIZE_MIN (O1HEAP_ALIGNMENT * 2U) + +/// This is risky, handle with care: if the allocation amount plus per-fragment overhead exceeds 2**(b-1), +/// where b is the pointer bit width, then ceil(log2(amount)) yields b; then 2**b causes an integer overflow. +/// To avoid this, we put a hard limit on fragment size (which is amount + per-fragment overhead): 2**(b-1) +#define FRAGMENT_SIZE_MAX ((SIZE_MAX >> 1U) + 1U) + +/// Normally we should subtract log2(FRAGMENT_SIZE_MIN) but log2 is bulky to compute using the preprocessor only. +/// We will certainly end up with unused bins this way, but it is cheap to ignore. +#define NUM_BINS_MAX (sizeof(size_t) * CHAR_BIT) + +static_assert((O1HEAP_ALIGNMENT & (O1HEAP_ALIGNMENT - 1U)) == 0U, "Not a power of 2"); +static_assert((FRAGMENT_SIZE_MIN & (FRAGMENT_SIZE_MIN - 1U)) == 0U, "Not a power of 2"); +static_assert((FRAGMENT_SIZE_MAX & (FRAGMENT_SIZE_MAX - 1U)) == 0U, "Not a power of 2"); + +typedef struct Fragment Fragment; + +typedef struct FragmentHeader +{ + Fragment* next; + Fragment* prev; + size_t size; + bool used; +} FragmentHeader; +static_assert(sizeof(FragmentHeader) <= O1HEAP_ALIGNMENT, "Memory layout error"); + +struct Fragment +{ + FragmentHeader header; + // Everything past the header may spill over into the allocatable space. The header survives across alloc/free. + Fragment* next_free; // Next free fragment in the bin; NULL in the last one. + Fragment* prev_free; // Same but points back; NULL in the first one. +}; +static_assert(sizeof(Fragment) <= FRAGMENT_SIZE_MIN, "Memory layout error"); + +struct O1HeapInstance +{ + Fragment* bins[NUM_BINS_MAX]; ///< Smallest fragments are in the bin at index 0. + size_t nonempty_bin_mask; ///< Bit 1 represents a non-empty bin; bin at index 0 is for the smallest fragments. + + O1HeapDiagnostics diagnostics; +}; + +/// The amount of space allocated for the heap instance. +/// Its size is padded up to O1HEAP_ALIGNMENT to ensure correct alignment of the allocation arena that follows. +#define INSTANCE_SIZE_PADDED ((sizeof(O1HeapInstance) + O1HEAP_ALIGNMENT - 1U) & ~(O1HEAP_ALIGNMENT - 1U)) + +static_assert(INSTANCE_SIZE_PADDED >= sizeof(O1HeapInstance), "Invalid instance footprint computation"); +static_assert((INSTANCE_SIZE_PADDED % O1HEAP_ALIGNMENT) == 0U, "Invalid instance footprint computation"); + +/// Undefined for zero argument. +O1HEAP_PRIVATE uint_fast8_t log2Floor(const size_t x) +{ + O1HEAP_ASSERT(x > 0); + // NOLINTNEXTLINE redundant cast to the same type. + return (uint_fast8_t) (((sizeof(x) * CHAR_BIT) - 1U) - ((uint_fast8_t) O1HEAP_CLZ(x))); +} + +/// Special case: if the argument is zero, returns zero. +O1HEAP_PRIVATE uint_fast8_t log2Ceil(const size_t x) +{ + // NOLINTNEXTLINE redundant cast to the same type. + return (x <= 1U) ? 0U : (uint_fast8_t) ((sizeof(x) * CHAR_BIT) - ((uint_fast8_t) O1HEAP_CLZ(x - 1U))); +} + +/// Raise 2 into the specified power. +/// You might be tempted to do something like (1U << power). WRONG! We humans are prone to forgetting things. +/// If you forget to cast your 1U to size_t or ULL, you may end up with undefined behavior. +O1HEAP_PRIVATE size_t pow2(const uint_fast8_t power) +{ + return ((size_t) 1U) << power; +} + +/// This is equivalent to pow2(log2Ceil(x)). Undefined for x<2. +O1HEAP_PRIVATE size_t roundUpToPowerOf2(const size_t x) +{ + O1HEAP_ASSERT(x >= 2U); + // NOLINTNEXTLINE redundant cast to the same type. + return ((size_t) 1U) << ((sizeof(x) * CHAR_BIT) - ((uint_fast8_t) O1HEAP_CLZ(x - 1U))); +} + +/// Links two fragments so that their next/prev pointers point to each other; left goes before right. +O1HEAP_PRIVATE void interlink(Fragment* const left, Fragment* const right) +{ + if (O1HEAP_LIKELY(left != NULL)) + { + left->header.next = right; + } + if (O1HEAP_LIKELY(right != NULL)) + { + right->header.prev = left; + } +} + +/// Adds a new fragment into the appropriate bin and updates the lookup mask. +O1HEAP_PRIVATE void rebin(O1HeapInstance* const handle, Fragment* const fragment) +{ + O1HEAP_ASSERT(handle != NULL); + O1HEAP_ASSERT(fragment != NULL); + O1HEAP_ASSERT(fragment->header.size >= FRAGMENT_SIZE_MIN); + O1HEAP_ASSERT((fragment->header.size % FRAGMENT_SIZE_MIN) == 0U); + const uint_fast8_t idx = log2Floor(fragment->header.size / FRAGMENT_SIZE_MIN); // Round DOWN when inserting. + O1HEAP_ASSERT(idx < NUM_BINS_MAX); + // Add the new fragment to the beginning of the bin list. + // I.e., each allocation will be returning the most-recently-used fragment -- good for caching. + fragment->next_free = handle->bins[idx]; + fragment->prev_free = NULL; + if (O1HEAP_LIKELY(handle->bins[idx] != NULL)) + { + handle->bins[idx]->prev_free = fragment; + } + handle->bins[idx] = fragment; + handle->nonempty_bin_mask |= pow2(idx); +} + +/// Removes the specified fragment from its bin. +O1HEAP_PRIVATE void unbin(O1HeapInstance* const handle, const Fragment* const fragment) +{ + O1HEAP_ASSERT(handle != NULL); + O1HEAP_ASSERT(fragment != NULL); + O1HEAP_ASSERT(fragment->header.size >= FRAGMENT_SIZE_MIN); + O1HEAP_ASSERT((fragment->header.size % FRAGMENT_SIZE_MIN) == 0U); + const uint_fast8_t idx = log2Floor(fragment->header.size / FRAGMENT_SIZE_MIN); // Round DOWN when removing. + O1HEAP_ASSERT(idx < NUM_BINS_MAX); + // Remove the bin from the free fragment list. + if (O1HEAP_LIKELY(fragment->next_free != NULL)) + { + fragment->next_free->prev_free = fragment->prev_free; + } + if (O1HEAP_LIKELY(fragment->prev_free != NULL)) + { + fragment->prev_free->next_free = fragment->next_free; + } + // Update the bin header. + if (O1HEAP_LIKELY(handle->bins[idx] == fragment)) + { + O1HEAP_ASSERT(fragment->prev_free == NULL); + handle->bins[idx] = fragment->next_free; + if (O1HEAP_LIKELY(handle->bins[idx] == NULL)) + { + handle->nonempty_bin_mask &= ~pow2(idx); + } + } +} + +// ---------------------------------------- PUBLIC API IMPLEMENTATION ---------------------------------------- + +O1HeapInstance* o1heapInit(void* const base, const size_t size) +{ + O1HeapInstance* out = NULL; + if ((base != NULL) && ((((size_t) base) % O1HEAP_ALIGNMENT) == 0U) && + (size >= (INSTANCE_SIZE_PADDED + FRAGMENT_SIZE_MIN))) + { + // Allocate the core heap metadata structure in the beginning of the arena. + O1HEAP_ASSERT(((size_t) base) % sizeof(O1HeapInstance*) == 0U); + out = (O1HeapInstance*) base; + out->nonempty_bin_mask = 0U; + for (size_t i = 0; i < NUM_BINS_MAX; i++) + { + out->bins[i] = NULL; + } + + // Limit and align the capacity. + size_t capacity = size - INSTANCE_SIZE_PADDED; + if (capacity > FRAGMENT_SIZE_MAX) + { + capacity = FRAGMENT_SIZE_MAX; + } + while ((capacity % FRAGMENT_SIZE_MIN) != 0) + { + O1HEAP_ASSERT(capacity > 0U); + capacity--; + } + O1HEAP_ASSERT((capacity % FRAGMENT_SIZE_MIN) == 0); + O1HEAP_ASSERT((capacity >= FRAGMENT_SIZE_MIN) && (capacity <= FRAGMENT_SIZE_MAX)); + + // Initialize the root fragment. + Fragment* const frag = (Fragment*) (void*) (((char*) base) + INSTANCE_SIZE_PADDED); + O1HEAP_ASSERT((((size_t) frag) % O1HEAP_ALIGNMENT) == 0U); + frag->header.next = NULL; + frag->header.prev = NULL; + frag->header.size = capacity; + frag->header.used = false; + frag->next_free = NULL; + frag->prev_free = NULL; + rebin(out, frag); + O1HEAP_ASSERT(out->nonempty_bin_mask != 0U); + + // Initialize the diagnostics. + out->diagnostics.capacity = capacity; + out->diagnostics.allocated = 0U; + out->diagnostics.peak_allocated = 0U; + out->diagnostics.peak_request_size = 0U; + out->diagnostics.oom_count = 0U; + } + + return out; +} + +void* o1heapAllocate(O1HeapInstance* const handle, const size_t amount) +{ + O1HEAP_ASSERT(handle != NULL); + O1HEAP_ASSERT(handle->diagnostics.capacity <= FRAGMENT_SIZE_MAX); + void* out = NULL; + + // If the amount approaches approx. SIZE_MAX/2, an undetected integer overflow may occur. + // To avoid that, we do not attempt allocation if the amount exceeds the hard limit. + // We perform multiple redundant checks to account for a possible unaccounted overflow. + if (O1HEAP_LIKELY((amount > 0U) && (amount <= (handle->diagnostics.capacity - O1HEAP_ALIGNMENT)))) + { + // Add the header size and align the allocation size to the power of 2. + // See "Timing-Predictable Memory Allocation In Hard Real-Time Systems", Herter, page 27. + const size_t fragment_size = roundUpToPowerOf2(amount + O1HEAP_ALIGNMENT); + O1HEAP_ASSERT(fragment_size <= FRAGMENT_SIZE_MAX); + O1HEAP_ASSERT(fragment_size >= FRAGMENT_SIZE_MIN); + O1HEAP_ASSERT(fragment_size >= amount + O1HEAP_ALIGNMENT); + O1HEAP_ASSERT((fragment_size & (fragment_size - 1U)) == 0U); // Is power of 2. + + const uint_fast8_t optimal_bin_index = log2Ceil(fragment_size / FRAGMENT_SIZE_MIN); // Use CEIL when fetching. + O1HEAP_ASSERT(optimal_bin_index < NUM_BINS_MAX); + const size_t candidate_bin_mask = ~(pow2(optimal_bin_index) - 1U); + + // Find the smallest non-empty bin we can use. + const size_t suitable_bins = handle->nonempty_bin_mask & candidate_bin_mask; + const size_t smallest_bin_mask = suitable_bins & ~(suitable_bins - 1U); // Clear all bits but the lowest. + if (O1HEAP_LIKELY(smallest_bin_mask != 0)) + { + O1HEAP_ASSERT((smallest_bin_mask & (smallest_bin_mask - 1U)) == 0U); // Is power of 2. + const uint_fast8_t bin_index = log2Floor(smallest_bin_mask); + O1HEAP_ASSERT(bin_index >= optimal_bin_index); + O1HEAP_ASSERT(bin_index < NUM_BINS_MAX); + + // The bin we found shall not be empty, otherwise it's a state divergence (memory corruption?). + Fragment* const frag = handle->bins[bin_index]; + O1HEAP_ASSERT(frag != NULL); + O1HEAP_ASSERT(frag->header.size >= fragment_size); + O1HEAP_ASSERT((frag->header.size % FRAGMENT_SIZE_MIN) == 0U); + O1HEAP_ASSERT(!frag->header.used); + unbin(handle, frag); + + // Split the fragment if it is too large. + const size_t leftover = frag->header.size - fragment_size; + frag->header.size = fragment_size; + O1HEAP_ASSERT(leftover < handle->diagnostics.capacity); // Overflow check. + O1HEAP_ASSERT(leftover % FRAGMENT_SIZE_MIN == 0U); // Alignment check. + if (O1HEAP_LIKELY(leftover >= FRAGMENT_SIZE_MIN)) + { + Fragment* const new_frag = (Fragment*) (void*) (((char*) frag) + fragment_size); + O1HEAP_ASSERT(((size_t) new_frag) % O1HEAP_ALIGNMENT == 0U); + new_frag->header.size = leftover; + new_frag->header.used = false; + interlink(new_frag, frag->header.next); + interlink(frag, new_frag); + rebin(handle, new_frag); + } + + // Update the diagnostics. + O1HEAP_ASSERT((handle->diagnostics.allocated % FRAGMENT_SIZE_MIN) == 0U); + handle->diagnostics.allocated += fragment_size; + O1HEAP_ASSERT(handle->diagnostics.allocated <= handle->diagnostics.capacity); + if (O1HEAP_LIKELY(handle->diagnostics.peak_allocated < handle->diagnostics.allocated)) + { + handle->diagnostics.peak_allocated = handle->diagnostics.allocated; + } + + // Finalize the fragment we just allocated. + O1HEAP_ASSERT(frag->header.size >= amount + O1HEAP_ALIGNMENT); + frag->header.used = true; + + out = ((char*) frag) + O1HEAP_ALIGNMENT; + } + } + + // Update the diagnostics. + if (O1HEAP_LIKELY(handle->diagnostics.peak_request_size < amount)) + { + handle->diagnostics.peak_request_size = amount; + } + if (O1HEAP_LIKELY((out == NULL) && (amount > 0U))) + { + handle->diagnostics.oom_count++; + } + + return out; +} + +void o1heapFree(O1HeapInstance* const handle, void* const pointer) +{ + O1HEAP_ASSERT(handle != NULL); + O1HEAP_ASSERT(handle->diagnostics.capacity <= FRAGMENT_SIZE_MAX); + if (O1HEAP_LIKELY(pointer != NULL)) // NULL pointer is a no-op. + { + Fragment* const frag = (Fragment*) (void*) (((char*) pointer) - O1HEAP_ALIGNMENT); + + // Check for heap corruption in debug builds. + O1HEAP_ASSERT(((size_t) frag) % sizeof(Fragment*) == 0U); + O1HEAP_ASSERT(((size_t) frag) >= (((size_t) handle) + INSTANCE_SIZE_PADDED)); + O1HEAP_ASSERT(((size_t) frag) <= + (((size_t) handle) + INSTANCE_SIZE_PADDED + handle->diagnostics.capacity - FRAGMENT_SIZE_MIN)); + O1HEAP_ASSERT(frag->header.used); // Catch double-free + O1HEAP_ASSERT(((size_t) frag->header.next) % sizeof(Fragment*) == 0U); + O1HEAP_ASSERT(((size_t) frag->header.prev) % sizeof(Fragment*) == 0U); + O1HEAP_ASSERT(frag->header.size >= FRAGMENT_SIZE_MIN); + O1HEAP_ASSERT(frag->header.size <= handle->diagnostics.capacity); + O1HEAP_ASSERT((frag->header.size % FRAGMENT_SIZE_MIN) == 0U); + + // Even if we're going to drop the fragment later, mark it free anyway to prevent double-free. + frag->header.used = false; + + // Update the diagnostics. It must be done before merging because it invalidates the fragment size information. + O1HEAP_ASSERT(handle->diagnostics.allocated >= frag->header.size); // Heap corruption check. + handle->diagnostics.allocated -= frag->header.size; + + // Merge with siblings and insert the returned fragment into the appropriate bin and update metadata. + Fragment* const prev = frag->header.prev; + Fragment* const next = frag->header.next; + const bool join_left = (prev != NULL) && (!prev->header.used); + const bool join_right = (next != NULL) && (!next->header.used); + if (join_left && join_right) // [ prev ][ this ][ next ] => [ ------- prev ------- ] + { + unbin(handle, prev); + unbin(handle, next); + prev->header.size += frag->header.size + next->header.size; + frag->header.size = 0; // Invalidate the dropped fragment headers to prevent double-free. + next->header.size = 0; + O1HEAP_ASSERT((prev->header.size % FRAGMENT_SIZE_MIN) == 0U); + interlink(prev, next->header.next); + rebin(handle, prev); + } + else if (join_left) // [ prev ][ this ][ next ] => [ --- prev --- ][ next ] + { + unbin(handle, prev); + prev->header.size += frag->header.size; + frag->header.size = 0; + O1HEAP_ASSERT((prev->header.size % FRAGMENT_SIZE_MIN) == 0U); + interlink(prev, next); + rebin(handle, prev); + } + else if (join_right) // [ prev ][ this ][ next ] => [ prev ][ --- this --- ] + { + unbin(handle, next); + frag->header.size += next->header.size; + next->header.size = 0; + O1HEAP_ASSERT((frag->header.size % FRAGMENT_SIZE_MIN) == 0U); + interlink(frag, next->header.next); + rebin(handle, frag); + } + else + { + rebin(handle, frag); + } + } +} + +bool o1heapDoInvariantsHold(const O1HeapInstance* const handle) +{ + O1HEAP_ASSERT(handle != NULL); + bool valid = true; + + // Check the bin mask consistency. + for (size_t i = 0; i < NUM_BINS_MAX; i++) // Dear compiler, feel free to unroll this loop. + { + const bool mask_bit_set = (handle->nonempty_bin_mask & pow2((uint_fast8_t) i)) != 0U; + const bool bin_nonempty = handle->bins[i] != NULL; + valid = valid && (mask_bit_set == bin_nonempty); + } + + // Create a local copy of the diagnostics struct. + const O1HeapDiagnostics diag = handle->diagnostics; + + // Capacity check. + valid = valid && (diag.capacity <= FRAGMENT_SIZE_MAX) && (diag.capacity >= FRAGMENT_SIZE_MIN) && + ((diag.capacity % FRAGMENT_SIZE_MIN) == 0U); + + // Allocation info check. + valid = valid && (diag.allocated <= diag.capacity) && ((diag.allocated % FRAGMENT_SIZE_MIN) == 0U) && + (diag.peak_allocated <= diag.capacity) && (diag.peak_allocated >= diag.allocated) && + ((diag.peak_allocated % FRAGMENT_SIZE_MIN) == 0U); + + // Peak request check + valid = valid && ((diag.peak_request_size < diag.capacity) || (diag.oom_count > 0U)); + if (diag.peak_request_size == 0U) + { + valid = valid && (diag.peak_allocated == 0U) && (diag.allocated == 0U) && (diag.oom_count == 0U); + } + else + { + valid = valid && // Overflow on summation is possible but safe to ignore. + (((diag.peak_request_size + O1HEAP_ALIGNMENT) <= diag.peak_allocated) || (diag.oom_count > 0U)); + } + + return valid; +} + +O1HeapDiagnostics o1heapGetDiagnostics(const O1HeapInstance* const handle) +{ + O1HEAP_ASSERT(handle != NULL); + const O1HeapDiagnostics out = handle->diagnostics; + return out; +} diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt index b2a7d37..02e27b2 100644 --- a/main/CMakeLists.txt +++ b/main/CMakeLists.txt @@ -9,6 +9,8 @@ idf_component_register( "persistent_settings.c" "discovery_beacon.c" "status_report.c" + "cyphal_node.c" + "can_listener.c" INCLUDE_DIRS "." EMBED_FILES website/index.html @@ -16,3 +18,5 @@ idf_component_register( website/script.js website/alpine.js ) + +target_compile_options(${COMPONENT_LIB} PRIVATE -Werror -Wextra -Wshadow -Wmissing-field-initializers -fanalyzer) \ No newline at end of file diff --git a/main/can_listener.c b/main/can_listener.c new file mode 100644 index 0000000..650b996 --- /dev/null +++ b/main/can_listener.c @@ -0,0 +1,213 @@ +#include "can_listener.h" + +#include "driver/twai.h" +#include "esp_log.h" +#include "freertos/queue.h" +#include "stdatomic.h" + +// The capacity of each CAN receive queue +#define CAN_RX_QUEUE_LEN 32 + +// The stack size of the can listener task. +#define STACK_SIZE 4096 + +// Name that will be used for logging +static const char *TAG = "can_listener"; + +// A struct that holds a CAN receiver queue that can be loaned +// with `can_listener_get()`. +typedef struct { + // The `can_listener_task` pushes `twai_message_t`s + // from the CAN bus onto all `rx_queue`s that are `in_use`. + QueueHandle_t rx_queue; + + // The storage that `rx_queue` uses. + uint8_t q_storage[CAN_RX_QUEUE_LEN * sizeof(twai_message_t)]; + + // The data structure that `rx_queue` uses. + StaticQueue_t q_buf; + + // True if this `rx_queue` has been loaned out with + // `can_listener_get()`. The `can_listener_task` only pushes + // messages to `can_receiver_t`s that are `in_use`. + atomic_bool in_use; + +} can_receiver_t; + +// All the `can_receiver_t` that can be loaned out with `can_listener_get()`. +static can_receiver_t can_receivers[CAN_LISTENERS_MAX]; + +// This queue stores pointers to all unused `can_receiver_t` +// in the array `can_receivers`. +// It's initialized to point to all the `can_receivers`. +// +// An item is popped when `can_listener_get()` is called +// and pushed when `can_listener_free()` is called. +static QueueHandle_t unused_can_receivers_queue = NULL; +static uint8_t unused_can_receiver_queue_storage[CAN_LISTENERS_MAX * + sizeof(can_receiver_t *)]; +static StaticQueue_t unused_can_receiver_queue_buf; + +// Task that continuously pushes messages from the CAN bus +// onto all the active `rx_queue`s in `can_receivers`. +static void can_listener_task(void *pvParameters); +static StackType_t can_listener_task_stack[STACK_SIZE]; +static StaticTask_t can_listener_task_mem; + +// Purely informational current status of the CAN listener. +static can_listener_status_t can_listener_status = {0}; +static SemaphoreHandle_t can_listener_status_mutex = NULL; +static StaticSemaphore_t can_listener_status_mutex_mem; + +esp_err_t can_listener_get_status(can_listener_status_t *status_out) { + if (can_listener_status_mutex == NULL) { + ESP_LOGE( + TAG, + "Can't get status because socketcand server hasn't been initialized."); + return ESP_FAIL; + } + assert(xSemaphoreTake(can_listener_status_mutex, portMAX_DELAY) == pdTRUE); + *status_out = can_listener_status; + assert(xSemaphoreGive(can_listener_status_mutex) == pdTRUE); + return ESP_OK; +} + +esp_err_t can_listener_start() { + // Create the queue that tracks unused `can_receiver_t`. + unused_can_receivers_queue = xQueueCreateStatic( + CAN_LISTENERS_MAX, sizeof(can_receiver_t *), + unused_can_receiver_queue_storage, &unused_can_receiver_queue_buf); + + if (unused_can_receivers_queue == NULL) { + ESP_LOGE(TAG, "Error initializing queue in can_listener."); + return ESP_FAIL; + } + + // Initialize every `can_receiver_t` in `can_receivers`. + // Add them to the `unused_can_receivers_queue`. + for (size_t i = 0; i < CAN_LISTENERS_MAX; i++) { + // Initialize the `can_receiver_t`. + atomic_store(&can_receivers[i].in_use, false); + can_receivers[i].rx_queue = + xQueueCreateStatic(CAN_RX_QUEUE_LEN, sizeof(twai_message_t), + can_receivers[i].q_storage, &can_receivers[i].q_buf); + + if (can_receivers[i].rx_queue == NULL) { + ESP_LOGE(TAG, "Error initializing queue in can_listener."); + return ESP_FAIL; + } + + // Add this `can_receiver_t` to the `unused_can_receivers_queue`. + can_receiver_t *can_receiver_ptr = &can_receivers[i]; + BaseType_t res = + xQueueSend(unused_can_receivers_queue, &can_receiver_ptr, 0); + if (res != pdTRUE) { + ESP_LOGE(TAG, "Error initializing queue in can_listener."); + return ESP_FAIL; + } + } + + // Initialize the mutex for accessing the `can_listener_status` struct. + can_listener_status_mutex = + xSemaphoreCreateMutexStatic(&can_listener_status_mutex_mem); + if (can_listener_status_mutex == NULL) { + ESP_LOGE(TAG, + "Unreachable. server_status_mutex couldn't be created in " + "can_listener."); + return ESP_FAIL; + } + + // Spawn the task that will insert incoming CAN messages + // to active queues in `can_receivers`. + xTaskCreateStatic(can_listener_task, "can_listener", + sizeof(can_listener_task_stack), NULL, 14, + can_listener_task_stack, &can_listener_task_mem); + + return ESP_OK; +} + +esp_err_t can_listener_get(QueueHandle_t *can_rx_out) { + // Get an unused `can_receiver_t`. + can_receiver_t *can_receiver; + BaseType_t res = xQueueReceive(unused_can_receivers_queue, &can_receiver, 0); + + // If there are no free `can_receiver_t`, return an error. + if (res != pdTRUE) { + return ESP_ERR_NO_MEM; + } + + xQueueReset(can_receiver->rx_queue); + *can_rx_out = can_receiver->rx_queue; + atomic_store(&can_receiver->in_use, true); + return ESP_OK; +} + +esp_err_t can_listener_free(const QueueHandle_t can_rx) { + // Find `can_rx` in `can_receivers`. + can_receiver_t *can_receiver = NULL; + for (size_t i = 0; i < CAN_LISTENERS_MAX; i++) { + if (can_rx == can_receivers[i].rx_queue) { + can_receiver = &can_receivers[i]; + break; + } + } + + // If the given `can_rx` isn't in our list of all `can_receivers`, + // return an error. + if (can_receiver == NULL) { + return ESP_ERR_INVALID_ARG; + } + + // Mark the `can_receiver` as unused. + atomic_store(&can_receiver->in_use, false); + + // Add the unused `can_receiver` to the `unused_can_receivers_queue`. + BaseType_t res = xQueueSend(unused_can_receivers_queue, &can_receiver, 0); + if (res != pdTRUE) { + ESP_LOGE(TAG, "Invalid state. Couldn't free CAN listener."); + return ESP_ERR_INVALID_STATE; + } + + return ESP_OK; +} + +void can_listener_enqueue_msg(const twai_message_t *message, + const QueueHandle_t skip_queue) { + // send the message to all `can_receivers` that are `in_use`. + for (int i = 0; i < CAN_LISTENERS_MAX; i++) { + if (atomic_load(&can_receivers[i].in_use) && + can_receivers[i].rx_queue != skip_queue) { + // append the message to the queue + if (xQueueSend(can_receivers[i].rx_queue, message, 0) != pdTRUE) { + ESP_LOGE(TAG, "CAN bus task receive queue %d full. Dropping message.", + i); + // Increment the status dropped frame counter + assert(xSemaphoreTake(can_listener_status_mutex, portMAX_DELAY) == + pdTRUE); + can_listener_status.can_bus_incoming_frames_dropped += 1; + assert(xSemaphoreGive(can_listener_status_mutex) == pdTRUE); + } + } + } +} + +static void can_listener_task(void *pvParameters) { + while (true) { + // receive a message from the CAN bus + twai_message_t received_msg = {0}; + esp_err_t res = twai_receive(&received_msg, portMAX_DELAY); + if (res != ESP_OK) { + ESP_LOGE(TAG, "Error receiving message from CAN bus: %s", + esp_err_to_name(res)); + continue; + } + + // send the message to the queues + can_listener_enqueue_msg(&received_msg, NULL); + + // Increment the status can bus counter + assert(xSemaphoreTake(can_listener_status_mutex, portMAX_DELAY) == pdTRUE); + can_listener_status.can_bus_frames_received += 1; + assert(xSemaphoreGive(can_listener_status_mutex) == pdTRUE); + } +} diff --git a/main/can_listener.h b/main/can_listener.h new file mode 100644 index 0000000..749ebc3 --- /dev/null +++ b/main/can_listener.h @@ -0,0 +1,46 @@ +#pragma once + +#include "driver/twai.h" +#include "esp_err.h" + +// The maximum number of CAN receive queues +// that may be loaned with `can_listener_get()` +// at any time. +// The socketcand_server will use up to 4 of these, +// and the OpenCyphal node may use 1. +#define CAN_LISTENERS_MAX 5 + +// The status of the CAN listener. +// Get the current status using `can_listener_get_status()`. +typedef struct { + uint64_t can_bus_frames_received; + uint64_t can_bus_incoming_frames_dropped; +} can_listener_status_t; + +// Starts a task that listens to CAN packets. +// Call this function before calling the other ones. +// Must only be called once. +// Must be called after the CAN driver is initialized. +esp_err_t can_listener_start(void); + +// Fills `status_out` with the current `can_listener_status_t`. +// Returns an error if the CAN listener hasn't been started yet. +esp_err_t can_listener_get_status(can_listener_status_t* status_out); + +// Fills `can_rx_queue` with a `QueueHandle_t`. +// The CAN listener task will send CAN frames to the queue +// as they are received. +// Up to `CAN_LISTENERS_MAX` queues can be active at any time. +// Returns `ESP_ERR_NO_MEM` if there are already `CAN_LISTENERS_MAX` loaned. +// Call `can_listener_free()` to return your queue. +esp_err_t can_listener_get(QueueHandle_t* can_rx_queue); + +// Frees the `QueueHandle_t` loaned by `can_listener_get()`. +// It can't be used after this. +esp_err_t can_listener_free(const QueueHandle_t can_rx_queue); + +// Pushes `message` to all the receiving queues except for `skip_queue`. +// This function is used to simulate receiving a CAN message. +// Set `skip_queue` to NULL to not skip any queues. +void can_listener_enqueue_msg(const twai_message_t* message, + const QueueHandle_t skip_queue); \ No newline at end of file diff --git a/main/cyphal_node.c b/main/cyphal_node.c new file mode 100644 index 0000000..0a6d080 --- /dev/null +++ b/main/cyphal_node.c @@ -0,0 +1,240 @@ +#include "cyphal_node.h" + +#include "can_listener.h" +#include "canard.h" +#include "esp_check.h" +#include "esp_log.h" +#include "esp_timer.h" +#include "freertos/FreeRTOS.h" +#include "o1heap.h" +#include "uavcan/node/Health_1_0.h" +#include "uavcan/node/Heartbeat_1_0.h" +#include "uavcan/node/Mode_1_0.h" + +// Size of the OpenCyphal O1 heap +#define HEAP_MEM_SIZE 32000 + +// Name that will be used for logging +static const char* TAG = "cyphal_node"; + +// The OpenCyphal O1 heap +static O1HeapInstance* o1_heap_instance = NULL; +static uint8_t o1_heap_mem[HEAP_MEM_SIZE] + __attribute__((aligned(O1HEAP_ALIGNMENT))); + +// Queue with stream of incoming CAN frames. +static QueueHandle_t can_rx_queue; + +// Canard instance for sending and receiving OpenCyphal messages. +static CanardInstance canard_instance; + +// Queue for sending OpenCyphal messages. +static CanardTxQueue canard_tx_queue; + +// The transfer ID of heartbeat messages. +// This is incremented after each transfer, +// with unsigned integer wrapping. +static uint8_t heartbeat_transfer_id = 0; + +// Subscribtion to heartbeat messages +static CanardRxSubscription heartbeat_subscription; + +// Task that listens to heartbeats from other OpenCyphal nodes. +// `pvParameters` should be NULL. +static void cyphal_listener_task(void* pvParameters); +static StackType_t cyphal_listener_task_stack[4096]; +static StaticTask_t cyphal_listener_task_mem; + +// Task that sends heartbeats to other OpenCyphal nodes. +// `pvParameters` should be NULL. +static void cyphal_heartbeat_task(void* pvParameters); +static StackType_t cyphal_heartbeat_task_stack[4096]; +static StaticTask_t cyphal_heartbeat_task_mem; + +// Purely informational current status of the OpenCyphal node. +static cyphal_node_status_t cyphal_node_status = {0}; +static SemaphoreHandle_t cyphal_node_status_mutex = NULL; +static StaticSemaphore_t cyphal_node_status_mutex_mem; + +esp_err_t cyphal_node_get_status(cyphal_node_status_t* status_out) { + if (cyphal_node_status_mutex == NULL) { + return ESP_FAIL; + } + assert(xSemaphoreTake(cyphal_node_status_mutex, portMAX_DELAY) == pdTRUE); + *status_out = cyphal_node_status; + assert(xSemaphoreGive(cyphal_node_status_mutex) == pdTRUE); + return ESP_OK; +} + +// Allocates memory on the o1 heap of this `CanardInstance`. +static void* allocate_mem(CanardInstance* ins, size_t amount) { + return o1heapAllocate(o1_heap_instance, amount); +} + +// Frees memory on the o1 heap of this `CanardInstance`. +static void free_mem(CanardInstance* ins, void* pointer) { + o1heapFree(o1_heap_instance, pointer); +} + +esp_err_t cyphal_node_start(uint8_t node_id) { + cyphal_node_status_mutex = + xSemaphoreCreateMutexStatic(&cyphal_node_status_mutex_mem); + if (cyphal_node_status_mutex == NULL) { + ESP_LOGE(TAG, "Unreachable. cyphal_node_status_mutex couldn't be created."); + return ESP_FAIL; + } + + // Initialize the O1 heap + o1_heap_instance = o1heapInit((void*)o1_heap_mem, sizeof(o1_heap_mem)); + if (o1_heap_instance == NULL) { + ESP_LOGE(TAG, "Couldn't initialize OpenCyphal O1 heap."); + return ESP_FAIL; + } + + // Get a CAN receive queue + esp_err_t err = can_listener_get(&can_rx_queue); + ESP_RETURN_ON_ERROR(err, TAG, + "OpenCyphal node couldn't get CAN receive queue."); + + // Initialize the OpenCyphal Canard instance + canard_instance = canardInit(&allocate_mem, &free_mem); + canard_instance.node_id = node_id; + + // Initialize the transmit queue + canard_tx_queue = canardTxInit(100, CANARD_MTU_CAN_CLASSIC); + + // Subscribe to heartbeat messages + int8_t res = canardRxSubscribe(&canard_instance, CanardTransferKindMessage, + uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_, + uavcan_node_Heartbeat_1_0_EXTENT_BYTES_, + CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, + &heartbeat_subscription); + if (res != 1) { + ESP_LOGE(TAG, + "OpenCyphal node couldn't subscribe to heartbeat. Error code: %d", + res); + can_listener_free(can_rx_queue); + return ESP_FAIL; + } + + // Spawn the OpenCyphal listener task + xTaskCreateStatic(cyphal_listener_task, "cyphal_listener_task", + sizeof(cyphal_listener_task_stack), NULL, 3, + cyphal_listener_task_stack, &cyphal_listener_task_mem); + + // Spawn the OpenCyphal node task + xTaskCreateStatic(cyphal_heartbeat_task, "cyphal_heartbeat_task", + sizeof(cyphal_heartbeat_task_stack), NULL, 3, + cyphal_heartbeat_task_stack, &cyphal_heartbeat_task_mem); + + return ESP_OK; +} + +static void cyphal_listener_task(void* pvParameters) { + while (true) { + // Receive the next frame from the CAN bus. + twai_message_t can_frame = {0}; + xQueueReceive(can_rx_queue, &can_frame, portMAX_DELAY); + + CanardMicrosecond micros = esp_timer_get_time(); + + CanardFrame canard_frame; + canard_frame.extended_can_id = can_frame.identifier; + canard_frame.payload = (void*)can_frame.data; + canard_frame.payload_size = (size_t)can_frame.data_length_code; + + // Have OpenCyphal process the received frame + CanardRxTransfer received_cyphal_msg; + int8_t res = canardRxAccept(&canard_instance, micros, &canard_frame, 0, + &received_cyphal_msg, NULL); + + if (res < 0) { + // Error occured + ESP_LOGE(TAG, "OpenCyphal error reading CAN frame. Error code: %d", res); + continue; + + } else if (res == 1) { + // Complete OpenCyphal message received + ESP_LOGD(TAG, "Received an OpenCyphal heartbeat from node ID: %d", + received_cyphal_msg.metadata.remote_node_id); + + assert(xSemaphoreTake(cyphal_node_status_mutex, portMAX_DELAY) == pdTRUE); + cyphal_node_status.heartbeats_received += 1; + assert(xSemaphoreGive(cyphal_node_status_mutex) == pdTRUE); + + free_mem(&canard_instance, received_cyphal_msg.payload); + } + } +} + +static void cyphal_heartbeat_task(void* pvParameters) { + while (true) { + // Send a heartbeat every second + vTaskDelay(pdMS_TO_TICKS(1000)); + + // Create a heartbeat message + CanardTransferMetadata transfer_metadata = { + .priority = CanardPriorityNominal, + .transfer_kind = CanardTransferKindMessage, + .port_id = uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_, + .remote_node_id = CANARD_NODE_ID_UNSET, + .transfer_id = heartbeat_transfer_id, + }; + heartbeat_transfer_id += 1; + + uavcan_node_Heartbeat_1_0 heartbeat = { + .uptime = esp_timer_get_time() / 1000000, + .health.value = uavcan_node_Health_1_0_NOMINAL, + .mode.value = uavcan_node_Mode_1_0_OPERATIONAL, + .vendor_specific_status_code = 0, + }; + + uint8_t heartbeat_buf[uavcan_node_Heartbeat_1_0_EXTENT_BYTES_]; + size_t heartbeat_buf_size = sizeof(heartbeat_buf); + + int8_t res = uavcan_node_Heartbeat_1_0_serialize_(&heartbeat, heartbeat_buf, + &heartbeat_buf_size); + if (res != 0) { + ESP_LOGE(TAG, "Error serializing heartbeat to send: %d", res); + continue; + } + + // Enqueue the heartbeat message. + int32_t result = + canardTxPush(&canard_tx_queue, &canard_instance, 0, &transfer_metadata, + heartbeat_buf_size, (void*)heartbeat_buf); + if (result < 1) { + ESP_LOGE(TAG, + "Canard error queueing heartbeat frame for transmission: %ld", + result); + continue; + } + + // Transmit all the CAN frames in the queue. + const CanardTxQueueItem* tx_item = NULL; + while ((tx_item = canardTxPeek(&canard_tx_queue)) != NULL) { + twai_message_t tx_frame = {0}; + tx_frame.identifier = tx_item->frame.extended_can_id; + tx_frame.data_length_code = tx_item->frame.payload_size; + tx_frame.extd = true; + memcpy(tx_frame.data, tx_item->frame.payload, + tx_item->frame.payload_size); + + esp_err_t err = twai_transmit(&tx_frame, pdMS_TO_TICKS(portMAX_DELAY)); + while (err != ESP_OK) { + ESP_LOGE(TAG, "Couldn't transmit OpenCyphal frame: %s", + esp_err_to_name(err)); + err = twai_transmit(&tx_frame, pdMS_TO_TICKS(portMAX_DELAY)); + } + + can_listener_enqueue_msg(&tx_frame, can_rx_queue); + + free_mem(&canard_instance, canardTxPop(&canard_tx_queue, tx_item)); + } + + // Finished sending heartbeat, so let's increment the counter. + assert(xSemaphoreTake(cyphal_node_status_mutex, portMAX_DELAY) == pdTRUE); + cyphal_node_status.heartbeats_sent += 1; + assert(xSemaphoreGive(cyphal_node_status_mutex) == pdTRUE); + } +} \ No newline at end of file diff --git a/main/cyphal_node.h b/main/cyphal_node.h new file mode 100644 index 0000000..5a2a0fa --- /dev/null +++ b/main/cyphal_node.h @@ -0,0 +1,20 @@ +#pragma once + +#include "esp_err.h" +#include "stdint.h" + +typedef struct { + int64_t heartbeats_received; + int64_t heartbeats_sent; +} cyphal_node_status_t; + + +// Starts an OpenCyphal node with `node_id` that sends +// a heartbeat every second. +// This function must be called only after +// `can_listener` has been started. +esp_err_t cyphal_node_start(uint8_t node_id); + +// Fills `status_out` with the current `cyphal_node_status_t`. +// Returns an error if the OpenCyphal node hasn't been started yet. +esp_err_t cyphal_node_get_status(cyphal_node_status_t *status_out); \ No newline at end of file diff --git a/main/discovery_beacon.c b/main/discovery_beacon.c index 29d20e7..6ed2b09 100644 --- a/main/discovery_beacon.c +++ b/main/discovery_beacon.c @@ -8,6 +8,7 @@ static const char* TAG = "discovery_beacon"; // Task that broadcasts the beacon. +// pvParameters should be ther local socket fd. static void discovery_beacon_task(void* pvParameters); static StackType_t task_stack[4096]; static StaticTask_t task_mem; @@ -54,9 +55,10 @@ static void discovery_beacon_task(void* pvParameters) { vTaskDelay(pdMS_TO_TICKS(2000)); int bytes_printed = 0; - int res = snprintf(msg_buf + bytes_printed, sizeof(msg_buf) - bytes_printed, - "\n"); + int res = + snprintf(msg_buf + bytes_printed, sizeof(msg_buf) - bytes_printed, + "\n"); bytes_printed += res; if (res < 0 || bytes_printed >= sizeof(msg_buf)) { ESP_LOGE(TAG, "Couldn't snprintf CAN beacon message."); @@ -66,7 +68,11 @@ static void discovery_beacon_task(void* pvParameters) { if (driver_setup_eth_netif != NULL && esp_netif_is_netif_up(driver_setup_eth_netif)) { esp_netif_ip_info_t ip_info; - ESP_ERROR_CHECK(esp_netif_get_ip_info(driver_setup_eth_netif, &ip_info)); + esp_err_t err = esp_netif_get_ip_info(driver_setup_eth_netif, &ip_info); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Discovery beacon task couldn't get ethernet IP info."); + continue; + } res = snprintf(msg_buf + bytes_printed, sizeof(msg_buf) - bytes_printed, @@ -81,7 +87,11 @@ static void discovery_beacon_task(void* pvParameters) { if (driver_setup_wifi_netif != NULL && esp_netif_is_netif_up(driver_setup_wifi_netif)) { esp_netif_ip_info_t ip_info; - ESP_ERROR_CHECK(esp_netif_get_ip_info(driver_setup_wifi_netif, &ip_info)); + esp_err_t err = esp_netif_get_ip_info(driver_setup_wifi_netif, &ip_info); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Discovery beacon task couldn't get Wi-Fi IP info."); + continue; + } res = snprintf(msg_buf + bytes_printed, sizeof(msg_buf) - bytes_printed, diff --git a/main/driver_setup.c b/main/driver_setup.c index 2efdfae..2891b7b 100644 --- a/main/driver_setup.c +++ b/main/driver_setup.c @@ -238,9 +238,16 @@ esp_err_t driver_setup_can(const twai_timing_config_t *timing_config) { twai_general_config_t g_config = TWAI_GENERAL_CONFIG_DEFAULT(GPIO_NUM_5, GPIO_NUM_35, TWAI_MODE_NORMAL); - // Change this line to enable/disable logging: - g_config.alerts_enabled = TWAI_ALERT_AND_LOG | TWAI_ALERT_ABOVE_ERR_WARN | - TWAI_ALERT_BUS_OFF | TWAI_ALERT_BUS_RECOVERED; + + // Sdkconfig configuration is set to put TWAI ISR into IRAM + // because this may reduce cache misses. + // This flag is required for that configuration. + g_config.intr_flags = ESP_INTR_FLAG_IRAM; + // Logging alerts doesn't work when TWAI ISR is in IRAM. + // To log alerts, change configuration to move it out of IRAM, + // and uncoment the lines below: + // g_config.alerts_enabled = TWAI_ALERT_AND_LOG | TWAI_ALERT_ABOVE_ERR_WARN | + // TWAI_ALERT_BUS_OFF | TWAI_ALERT_BUS_RECOVERED; g_config.tx_queue_len = 32; g_config.rx_queue_len = 32; twai_filter_config_t f_config = TWAI_FILTER_CONFIG_ACCEPT_ALL(); diff --git a/main/frame_io.c b/main/frame_io.c index 6cf065d..bb8c7c6 100644 --- a/main/frame_io.c +++ b/main/frame_io.c @@ -42,7 +42,8 @@ esp_err_t frame_io_read_next_frame(frame_io_messenger *reader, char *buf, // the buffer is empty, so read more bytes } else { - int bytes_read = read(reader->socket_fd, reader->buf, sizeof(buf)); + int bytes_read = + read(reader->socket_fd, reader->buf, sizeof(reader->buf)); if (bytes_read < 0 && errno != EINTR && errno != EAGAIN && errno != EWOULDBLOCK) { diff --git a/main/frame_io.h b/main/frame_io.h index 63afa28..5399a96 100644 --- a/main/frame_io.h +++ b/main/frame_io.h @@ -6,8 +6,11 @@ // Used to read < > frames one at a time. typedef struct { - // Buffer for reading socketcand - char buf[1024]; + // Internal buffer. + // Note: this does NOT need to be able to fit + // a whole < > frame. It is only used to + // reduce the number of expensive `read()` calls by buffering. + char buf[4096]; // Points to the first character in the buffer. // MUST be initialized to zero. diff --git a/main/http_server.c b/main/http_server.c index 2376d43..97faa83 100644 --- a/main/http_server.c +++ b/main/http_server.c @@ -387,5 +387,30 @@ static esp_err_t update_persistent_settings_from_json( return err; } + // read enable_cyphal field + err = httpd_query_key_value(shared_post_buf, "enable_cyphal", arg_buf, + sizeof(arg_buf)); + if (err == ESP_OK) { + if (strncasecmp(arg_buf, "true", 4) == 0) + cnf->enable_cyphal = true; + else + cnf->enable_cyphal = false; + } else if (err != ESP_ERR_NOT_FOUND) { + return err; + } + + // read cyphal_node_id field + err = httpd_query_key_value(shared_post_buf, "cyphal_node_id", arg_buf, + sizeof(arg_buf)); + if (err == ESP_OK) { + uint32_t num = strtol(arg_buf, NULL, 10); + if (num > 127) { + return ESP_FAIL; + } + cnf->cyphal_node_id = num; + } else if (err != ESP_ERR_NOT_FOUND) { + return err; + } + return ESP_OK; } \ No newline at end of file diff --git a/main/main.c b/main/main.c index 7bb15a3..54d1974 100644 --- a/main/main.c +++ b/main/main.c @@ -1,3 +1,5 @@ +#include "can_listener.h" +#include "cyphal_node.h" #include "discovery_beacon.h" #include "driver_setup.h" #include "esp_log.h" @@ -92,6 +94,14 @@ void app_main(void) { esp_err_to_name(err)); } + // Start the task that will listen for incoming CAN messages. + // Requried for the socketcand server to run. + err = can_listener_start(); + if (err != ESP_OK) { + ESP_LOGE(TAG, "CRITICAL: Couldn't start CAN listener: %s", + esp_err_to_name(err)); + } + // start HTTP server used for configuring stuff err = start_http_server(); if (err != ESP_OK) { @@ -100,7 +110,7 @@ void app_main(void) { } // Start the socketcand translation server - err = socketcand_server_start(29536); + err = socketcand_server_start(); if (err != ESP_OK) { ESP_LOGE(TAG, "CRITICAL: Couldn't start socketcand server: %s", esp_err_to_name(err)); @@ -113,6 +123,15 @@ void app_main(void) { esp_err_to_name(err)); } + // Start the OpenCyphal node. + if (persistent_settings->enable_cyphal) { + err = cyphal_node_start(persistent_settings->cyphal_node_id); + if (err != ESP_OK) { + ESP_LOGE(TAG, "CRITICAL: Couldn't start OpenCyphal node: %s", + esp_err_to_name(err)); + } + } + // Log network status after giving some time // for connections to establish. vTaskDelay(pdMS_TO_TICKS(10000)); diff --git a/main/persistent_settings.c b/main/persistent_settings.c index e66cf07..f523bcc 100644 --- a/main/persistent_settings.c +++ b/main/persistent_settings.c @@ -124,6 +124,12 @@ esp_err_t persistent_settings_load(void) { "\",\n" "\"can_bitrate\": " + "%d,\n" + + "\"enable_cyphal\": " + "%s,\n" + + "\"cyphal_node_id\": " "%d\n" "}\n", @@ -139,7 +145,9 @@ esp_err_t persistent_settings_load(void) { IP2STR(&persistent_settings->wifi_ip_info.ip), IP2STR(&persistent_settings->wifi_ip_info.netmask), IP2STR(&persistent_settings->wifi_ip_info.gw), - persistent_settings->can_bitrate); + persistent_settings->can_bitrate, + persistent_settings->enable_cyphal ? "true" : "false", + persistent_settings->cyphal_node_id); if (bytes_written < 0 || bytes_written >= sizeof(persistent_settings_json_data)) { diff --git a/main/persistent_settings.h b/main/persistent_settings.h index d3f5904..69bdde1 100644 --- a/main/persistent_settings.h +++ b/main/persistent_settings.h @@ -46,6 +46,12 @@ typedef struct { // Bitrate of CAN interface enum can_bitrate_setting can_bitrate; + // OpenCyphal node enabled? + bool enable_cyphal; + + // ID of Cyphal Node if enabled. + uint8_t cyphal_node_id; + } persistent_settings_t; // Default `persistent_settings_t`. @@ -63,6 +69,8 @@ static const persistent_settings_t persistent_settings_default = { .wifi_ip_info.netmask.addr = ESP_IP4TOADDR(255, 255, 255, 0), .wifi_ip_info.gw.addr = ESP_IP4TOADDR(192, 168, 2, 1), .can_bitrate = CAN_KBITS_500, + .enable_cyphal = false, + .cyphal_node_id = 98, }; // Pointer to the current persistent settings. diff --git a/main/socketcand_server.c b/main/socketcand_server.c index 645fc60..868189f 100644 --- a/main/socketcand_server.c +++ b/main/socketcand_server.c @@ -1,5 +1,6 @@ #include "socketcand_server.h" +#include "can_listener.h" #include "driver/twai.h" #include "esp_intr_alloc.h" #include "esp_log.h" @@ -11,47 +12,33 @@ // Name that will be used for logging static const char *TAG = "socketcand_server"; -// The length of the `can_rx_queue` in each `client_handler_data_t`. -#define CAN_RX_QUEUE_LENGTH 32 - // Maximum number of TCP socketcand client connections // that can be served simultaneously before new connections // are dropped. -#define MAX_CLIENTS 5 +#define MAX_CLIENTS 4 // Stack size allocated for every FreeRTOS task. #define STACK_SIZE 4096 -// Set the `socketcand_translate_frame_t` `user_data` value -// to this, to indicate this is a normal CAN bus frame. -#define SOCKETCAND_NORMAL_FRAME 0 - -// Set the `socketcand_translate_frame_t` `user_data` value -// to this, to indicate this isn't a CAN bus frame. +// Set the `twai_message_t` `data_length_code` to this value +// to indicate this isn't a CAN bus frame. // If a task pops this off the queue, that means it should // exit and disconnect from its TCP client. -#define SOCKETCAND_INTERRUPT_FRAME 1 +#define CAN_INTERRUPT_FRAME 0xff -// Data that tasks serving a client get a pointer to. +// Data that each client handler gets a pointer to. typedef struct { - // The `can_listener_task` pushes `socketcand_translate_frame_t`s - // from the CAN bus onto all the active `can_rx_queue`s. - // Each `serve_client_task` then pops from the queue at its assigned index. + // Queue of `twai_message_t` incoming from the CAN bus. + // Initialized using `can_listener_get()`. QueueHandle_t can_rx_queue; - // The data structure that `can_rx_queue` uses. - StaticQueue_t can_rx_queue_buffer; - - // The storage that `can_rx_queue` uses. - uint8_t can_rx_queue_storage[CAN_RX_QUEUE_LENGTH * - sizeof(socketcand_translate_frame_t)]; - // Messenger used for communicating with TCP client. + // Its `socket_fd` is set to -1 when it isn't connected to any clients. frame_io_messenger tcp_messenger; - // Mutex that tasks serving the client take - // during the critical section of closing the connection and deleting - // themselves. + // Mutex that the 2 tasks serving the client take + // during the critical section of closing the connection + // and deleting themselves. SemaphoreHandle_t handler_task_delete_mutex; // FreeRTOS memory for the `handler_task_delete_mutex`. @@ -71,7 +58,7 @@ typedef struct { } client_handler_data_t; -// An array of `client_handler_data_t`. Each group of tasks handling +// An array of `client_handler_data_t`. Each pair of tasks handling // a client gets assigned a pointer to one of the elements. static client_handler_data_t client_handler_datas[MAX_CLIENTS]; @@ -81,47 +68,48 @@ static client_handler_data_t client_handler_datas[MAX_CLIENTS]; // An item is popped when spawning a new task to handle a client, // and pushed again once the client disconnects. static QueueHandle_t unused_client_handler_data_queue = NULL; -StaticQueue_t unused_client_handler_data_queue_buffer; -uint8_t +static StaticQueue_t unused_client_handler_data_queue_buffer; +static uint8_t unused_client_handler_data_queue_storage[MAX_CLIENTS * sizeof(client_handler_data_t *)]; +// Returns a pointer to an initialized `client_handler_data_t` from +// `unused_client_handler_data_queue`. +// Returns NULL if all `MAX_CLIENTS` of them are already in use. +static client_handler_data_t *get_client_handler_data(int client_sock); + +// Resets the `client_handler_data_t` +// and sends it to the `unused_client_handler_data_queue`. +static void free_client_handler_data( + client_handler_data_t *client_handler_data); + // Task that continuously listens for incoming TCP connections. // pvParameters should be a listener socket FD. static void run_server_task(void *pvParameters); static StackType_t run_server_task_stack[STACK_SIZE]; static StaticTask_t run_server_task_mem; -// Task that continuously pushes messages from the CAN bus -// onto all the active `can_rx_queue`s. -static void can_listener_task(void *pvParameters); -static StackType_t can_listener_task_stack[STACK_SIZE]; -static StaticTask_t can_listener_task_mem; - -// Pushes the `message` to all of the active `can_rx_queue`s. -// This will cause it to be sent to all TCP socketcand clients EXCEPT -// for `skip_client`, which will be omitted. -// Set `skip_client` to `NULL` to not skip any clients. -static void enqueue_can_message(socketcand_translate_frame_t *message, - const client_handler_data_t *skip_client); - // Task that serves a client. -// pvParameters should be the index of the client. +// pvParameters should be a pointer to a `client_handler_data_t`. static void serve_client_task(void *pvParameters); // Task that forwards messages from TCP to CAN bus. -// pvParameters should be the index of the client. +// pvParameters should be a pointer to a `client_handler_data_t`. static void socketcand_to_bus_task(void *pvParameters); // Task that forwards messages from CAN bus to TCP. -// pvParameters should be the index of the client. +// pvParameters should be a pointer to a `client_handler_data_t`. static void bus_to_socketcand_task(void *pvParameters); -// Deletes one of the two tasks that are using `client_handler_data`. +// Both tasks serving a client must call this function +// before returning. +// This function deletes the task and does some things +// to set everything up for the next user of this `client_handler_data`. // See comments inside the function for more details. static void delete_serve_client_task( client_handler_data_t *client_handler_data); +// Purely informational status of this server static socketcand_server_status_t server_status = {0}; static SemaphoreHandle_t server_status_mutex = NULL; static StaticSemaphore_t server_status_mutex_mem; @@ -133,17 +121,15 @@ esp_err_t socketcand_server_status(socketcand_server_status_t *status_out) { "Can't get status because socketcand server hasn't been initialized."); return ESP_FAIL; } - if (xSemaphoreTake(server_status_mutex, portMAX_DELAY) != pdTRUE) { - ESP_LOGE(TAG, "Unreachable: couldn't acquire server_status_mutex."); - return ESP_FAIL; - } - memcpy(status_out, &server_status, sizeof(server_status)); - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); + *status_out = server_status; + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); + return ESP_OK; } -esp_err_t socketcand_server_start(uint16_t port) { +esp_err_t socketcand_server_start(void) { // create a TCP socket int listen_sock = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); if (listen_sock < 0) { @@ -161,11 +147,11 @@ esp_err_t socketcand_server_start(uint16_t port) { return ESP_FAIL; } - // Bind the TCP socket + // Bind the listener TCP socket struct sockaddr_in server_addr = {0}; server_addr.sin_addr.s_addr = htonl(INADDR_ANY); server_addr.sin_family = AF_INET; - server_addr.sin_port = htons(port); + server_addr.sin_port = htons(29536); err = bind(listen_sock, (struct sockaddr *)&server_addr, sizeof(server_addr)); if (err != 0) { ESP_LOGE(TAG, "Socket unable to bind: errno %d", errno); @@ -181,10 +167,6 @@ esp_err_t socketcand_server_start(uint16_t port) { return ESP_FAIL; } - // Log that we've started listening. - ESP_LOGD(TAG, "Started socketcand TCP server listening on %s:%d", - inet_ntoa(server_addr.sin_addr), ntohs(server_addr.sin_port)); - // Initialize the mutex for accessing the `server_status` struct. server_status_mutex = xSemaphoreCreateMutexStatic(&server_status_mutex_mem); if (server_status_mutex == NULL) { @@ -192,17 +174,24 @@ esp_err_t socketcand_server_start(uint16_t port) { return ESP_FAIL; } - // Initialize `client_handler_datas`. - for (int i = 0; i < MAX_CLIENTS; i++) { - client_handler_datas[i].can_rx_queue = xQueueCreateStatic( - CAN_RX_QUEUE_LENGTH, sizeof(socketcand_translate_frame_t), - client_handler_datas[i].can_rx_queue_storage, - &client_handler_datas[i].can_rx_queue_buffer); + // Create the queue that holds pointers to all the unused + // `client_handler_data_t`. + unused_client_handler_data_queue = + xQueueCreateStatic(MAX_CLIENTS, sizeof(client_handler_data_t *), + unused_client_handler_data_queue_storage, + &unused_client_handler_data_queue_buffer); + if (unused_client_handler_data_queue == NULL) { + ESP_LOGE( + TAG, + "Unreachable. unused_client_handler_data_queue couldn't be created."); + return ESP_FAIL; + } - if (client_handler_datas[i].can_rx_queue == NULL) { - ESP_LOGE(TAG, "Unreachable. A can_rx_queue couldn't be created."); - return ESP_FAIL; - } + // Initialize `client_handler_datas` + // and `unused_client_handler_data_queue`. + for (int i = 0; i < MAX_CLIENTS; i++) { + // Initialize the `client_handler_data_t`. + client_handler_datas[i].can_rx_queue = NULL; client_handler_datas[i].tcp_messenger.socket_fd = -1; @@ -214,22 +203,9 @@ esp_err_t socketcand_server_start(uint16_t port) { "Unreachable. A handler_task_delete_mutex couldn't be created."); return ESP_FAIL; } - } - - // initialize the queue that holds all the unused client_handler_data - unused_client_handler_data_queue = - xQueueCreateStatic(MAX_CLIENTS, sizeof(client_handler_data_t *), - unused_client_handler_data_queue_storage, - &unused_client_handler_data_queue_buffer); - if (unused_client_handler_data_queue == NULL) { - ESP_LOGE( - TAG, - "Unreachable. unused_client_handler_data_queue couldn't be created."); - return ESP_FAIL; - } - - for (int i = 0; i < MAX_CLIENTS; i++) { + // Push a pointer to this `client_handler_data_t` to the + // `unused_client_handler_data_queue`. const client_handler_data_t *pointer_to_client_handler_data = &client_handler_datas[i]; if (xQueueSend(unused_client_handler_data_queue, @@ -241,11 +217,9 @@ esp_err_t socketcand_server_start(uint16_t port) { } } - // Task that continuously pushes messages from the CAN bus - // onto all the active can_rx_queues. - xTaskCreateStatic(can_listener_task, "can_listener_task", - sizeof(can_listener_task_stack), NULL, 14, - can_listener_task_stack, &can_listener_task_mem); + // Log that we've started listening. + ESP_LOGD(TAG, "Started socketcand TCP server listening on %s:%d", + inet_ntoa(server_addr.sin_addr), ntohs(server_addr.sin_port)); // Task that continuously listens for incoming TCP connections. // pvParameters is set to the listener socket FD. @@ -256,6 +230,54 @@ esp_err_t socketcand_server_start(uint16_t port) { return ESP_OK; } +static client_handler_data_t *get_client_handler_data(int client_sock) { + client_handler_data_t *client_handler_data_ptr; + BaseType_t res = xQueueReceive(unused_client_handler_data_queue, + &client_handler_data_ptr, 0); + if (res != pdTRUE) { + return NULL; + } + + // Fill out the `can_rx_queue` of this `client_handler_data`. + esp_err_t err = can_listener_get(&client_handler_data_ptr->can_rx_queue); + if (err != ESP_OK) { + assert(xQueueSend(unused_client_handler_data_queue, + &client_handler_data_ptr, 0) == pdTRUE); + return NULL; + } + + // Initialize the `tcp_messenger`. + client_handler_data_ptr->tcp_messenger.l = 0; + client_handler_data_ptr->tcp_messenger.r = 0; + client_handler_data_ptr->tcp_messenger.socket_fd = client_sock; + + return client_handler_data_ptr; +} + +static void free_client_handler_data( + client_handler_data_t *client_handler_data) { + // Close client connection if one is still open + if (client_handler_data->tcp_messenger.socket_fd != -1) { + shutdown(client_handler_data->tcp_messenger.socket_fd, 0); + close(client_handler_data->tcp_messenger.socket_fd); + } + + // Reset the `tcp_messenger`. + client_handler_data->tcp_messenger.l = 0; + client_handler_data->tcp_messenger.r = 0; + client_handler_data->tcp_messenger.socket_fd = -1; + + esp_err_t err = can_listener_free(client_handler_data->can_rx_queue); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Unreachable. Couldn't free CAN RX queue."); + abort(); + } + client_handler_data->can_rx_queue = NULL; + + assert(xQueueSend(unused_client_handler_data_queue, &client_handler_data, + 0) == pdTRUE); +} + static void run_server_task(void *pvParameters) { int listen_sock = (int)pvParameters; @@ -272,20 +294,17 @@ static void run_server_task(void *pvParameters) { } // Log the origin of the incoming connection - ESP_LOGI(TAG, "Accepted socketcand client TCP connectrion from: %s", + ESP_LOGI(TAG, "Accepted socketcand client TCP connection from: %s", inet_ntoa(source_addr.sin_addr)); - // Assign a pointer to an unused `client_handler_data_t` to the task - // about to be spawned. - client_handler_data_t *client_handler_data = NULL; - - BaseType_t res = xQueueReceive(unused_client_handler_data_queue, - &client_handler_data, 0); + // Get a pointer to an unused `client_handler_data_t`. + client_handler_data_t *client_handler_data = + get_client_handler_data(client_sock); - // if all the handler data is already in use - if (res != pdTRUE) { + if (client_handler_data == NULL) { ESP_LOGE(TAG, - "Dropping socketcand TCP connection because reached limit of %d " + "Dropping incoming socketcand TCP connection because reached " + "limit of %d " "simultaneous clients.", MAX_CLIENTS); shutdown(client_sock, 0); @@ -293,21 +312,13 @@ static void run_server_task(void *pvParameters) { continue; } - // set up the frame messenger and queue for this index - client_handler_data->tcp_messenger.l = 0; - client_handler_data->tcp_messenger.r = 0; - client_handler_data->tcp_messenger.socket_fd = client_sock; - - xQueueReset(client_handler_data->can_rx_queue); - // spawn a thread to serve the client with this index xTaskCreateStatic(serve_client_task, "serving_socketcand_client", sizeof(client_handler_data->free_rtos_stack_1), - (void *)client_handler_data, 10, + (void *)client_handler_data, 11, client_handler_data->free_rtos_stack_1, &client_handler_data->free_rtos_mem_1); } - vTaskDelete(NULL); } static void serve_client_task(void *pvParameters) { @@ -319,39 +330,54 @@ static void serve_client_task(void *pvParameters) { while (true) { // write a handshake frame int32_t phase = socketcand_translate_open_raw(frame_str, sizeof(frame_str)); - frame_io_write_str(client_handler_data->tcp_messenger.socket_fd, frame_str); + esp_err_t err = frame_io_write_str( + client_handler_data->tcp_messenger.socket_fd, frame_str); + if (err != ESP_OK) { + ESP_LOGE(TAG, + "Disconnecting because couldn't send socketcand to client: %s", + esp_err_to_name(err)); + free_client_handler_data(client_handler_data); + vTaskDelete(NULL); + return; + } if (phase == -1) { - ESP_LOGE(TAG, - "Buffer too small when negotiating socketcand rawmode. Closing " - "connection."); - delete_serve_client_task(client_handler_data); + ESP_LOGE( + TAG, + "Unreachable. Buffer too small when negotiating socketcand rawmode."); + free_client_handler_data(client_handler_data); + vTaskDelete(NULL); return; } else if (phase == 0) { ESP_LOGE(TAG, - "Client sent unknown socketcand message '%s 'while negotiating " + "Client sent unknown socketcand message '%s' while negotiating " "rawmode. " "Closing connection.", frame_str); // Increment the server status error counter - xSemaphoreTake(server_status_mutex, portMAX_DELAY); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); server_status.invalid_socketcand_frames_received += 1; - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); - delete_serve_client_task(client_handler_data); + free_client_handler_data(client_handler_data); + vTaskDelete(NULL); return; + } else if (phase == 3) { - break; // socketcand rawmode successfully established + // Socketcand rawmode successfully established. + // Exit this negotiation loop. + break; } - // read the next < > frame from the client - esp_err_t err = frame_io_read_next_frame( - &client_handler_data->tcp_messenger, frame_str, sizeof(frame_str)); + // read the next rawmode negotiation frame from the client + err = frame_io_read_next_frame(&client_handler_data->tcp_messenger, + frame_str, sizeof(frame_str)); if (err != ESP_OK) { - ESP_LOGI( - TAG, - "Error reading socketcand frame from client. Closing connection."); - delete_serve_client_task(client_handler_data); + ESP_LOGI(TAG, + "Error reading socketcand rawmode negotiation < > frame from " + "client. Closing connection."); + free_client_handler_data(client_handler_data); + vTaskDelete(NULL); return; } } @@ -372,59 +398,56 @@ static void socketcand_to_bus_task(void *pvParameters) { char frame_str[SOCKETCAND_RAW_MAX_LEN]; while (true) { - // Try to read the next < > frame from the network. + // Try to read the next data < > frame from the network. esp_err_t err = frame_io_read_next_frame( &client_handler_data->tcp_messenger, frame_str, sizeof(frame_str)); if (err != ESP_OK) { - ESP_LOGD(TAG, "Couldn't read the next < > frame from socketcand."); + ESP_LOGD( + TAG, + "Couldn't read the next < > frame from socketcand. Disconnecting."); delete_serve_client_task(client_handler_data); return; } // Parse the message - socketcand_translate_frame_t received_msg; - if (socketcand_translate_string_to_frame(frame_str, &received_msg) == -1) { - ESP_LOGE(TAG, "Couldn't parse socketcand frame from client."); + twai_message_t received_msg = {0}; + err = socketcand_translate_string_to_frame(frame_str, &received_msg); + if (err != ESP_OK) { + ESP_LOGE(TAG, + "Couldn't parse socketcand frame from client. Disconnecting."); // Increment the server status error counter - xSemaphoreTake(server_status_mutex, portMAX_DELAY); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); server_status.invalid_socketcand_frames_received += 1; - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); delete_serve_client_task(client_handler_data); return; } // Increment the server status can bus counter - xSemaphoreTake(server_status_mutex, portMAX_DELAY); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); server_status.socketcand_frames_received += 1; - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); - // Send the message to other TCP socketcand clients. - enqueue_can_message(&received_msg, client_handler_data); - - // Send the frame over CAN - twai_message_t twai_message = {0}; - memcpy(twai_message.data, received_msg.data, received_msg.len); - twai_message.data_length_code = received_msg.len; - twai_message.extd = received_msg.ext; - twai_message.identifier = received_msg.id; - - esp_err_t can_res = twai_transmit(&twai_message, 0); - - if (can_res == ESP_OK) { + // Enqueue the frame for CAN transmission, with a timeout of 2 seconds + err = twai_transmit(&received_msg, pdMS_TO_TICKS(2000)); + if (err == ESP_OK) { // Increment the server status can bus counter - xSemaphoreTake(server_status_mutex, portMAX_DELAY); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); server_status.can_bus_frames_sent += 1; - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); } else { - ESP_LOGE(TAG, "Couldn't transmit frame to CAN. %s", - esp_err_to_name(can_res)); + ESP_LOGE(TAG, "Couldn't transmit frame to CAN. %s", esp_err_to_name(err)); - xSemaphoreTake(server_status_mutex, portMAX_DELAY); - server_status.can_bus_frames_send_fails += 1; - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); + server_status.can_bus_frames_send_timeouts += 1; + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); } + + // Send the message to other TCP socketcand clients. + can_listener_enqueue_msg(&received_msg, client_handler_data->can_rx_queue); } + delete_serve_client_task(client_handler_data); return; } @@ -436,97 +459,59 @@ static void bus_to_socketcand_task(void *pvParameters) { char buf[SOCKETCAND_RAW_MAX_LEN]; while (true) { - // read a frame from the CAN bus queue - socketcand_translate_frame_t frame; - BaseType_t res = - xQueueReceive(client_handler_data->can_rx_queue, &frame, portMAX_DELAY); + // Receive an incoming frame from the CAN bus queue + twai_message_t twai_msg; + BaseType_t res = xQueueReceive(client_handler_data->can_rx_queue, &twai_msg, + portMAX_DELAY); if (res != pdTRUE) { - // Should be unreachable - ESP_LOGE(TAG, "Couldn't receive CAN bus frame from queue. Panicking."); - abort(); + ESP_LOGE(TAG, "Unreachable. Couldn't receive CAN bus frame from queue."); + delete_serve_client_task(client_handler_data); + return; } // If received a special frame that means we should // disconnect from the client. - if (frame.user_data == SOCKETCAND_INTERRUPT_FRAME) { + if (twai_msg.data_length_code == CAN_INTERRUPT_FRAME) { delete_serve_client_task(client_handler_data); return; } + // `socketcand_translate_frame_to_string()` requires the current time. int64_t micros = esp_timer_get_time(); int64_t secs = micros / 1000000; int64_t usecs = micros % 1000000; // write the message to TCP - if (socketcand_translate_frame_to_string(buf, sizeof(buf), &frame, secs, - usecs) != ESP_OK) { + esp_err_t err = socketcand_translate_frame_to_string( + buf, sizeof(buf), &twai_msg, secs, usecs); + if (err != ESP_OK) { ESP_LOGE(TAG, "Couldn't translate CAN frame to socketcand < > string."); delete_serve_client_task(client_handler_data); return; } - if (frame_io_write_str(client_handler_data->tcp_messenger.socket_fd, buf) != - ESP_OK) { + + err = frame_io_write_str(client_handler_data->tcp_messenger.socket_fd, buf); + if (err != ESP_OK) { ESP_LOGD(TAG, "Error sending socketcand frame to client over TCP."); delete_serve_client_task(client_handler_data); return; } // Increment the server status socketcand sent counter - xSemaphoreTake(server_status_mutex, portMAX_DELAY); + assert(xSemaphoreTake(server_status_mutex, portMAX_DELAY) == pdTRUE); server_status.socketcand_frames_sent += 1; - xSemaphoreGive(server_status_mutex); + assert(xSemaphoreGive(server_status_mutex) == pdTRUE); } delete_serve_client_task(client_handler_data); return; } -static void can_listener_task(void *pvParameters) { - while (true) { - // receive a message from the CAN bus - twai_message_t received_msg; - esp_err_t res; - while ((res = twai_receive(&received_msg, portMAX_DELAY)) != ESP_OK) { - ESP_LOGE(TAG, "Error receiving message from CAN bus: %s", - esp_err_to_name(res)); - } - - // Increment the server status can bus counter - xSemaphoreTake(server_status_mutex, portMAX_DELAY); - server_status.can_bus_frames_received += 1; - xSemaphoreGive(server_status_mutex); - - // put the message in a socketcand struct - socketcand_translate_frame_t frame = {0}; - memcpy(frame.data, received_msg.data, received_msg.data_length_code); - frame.ext = received_msg.extd; - frame.id = received_msg.identifier; - frame.len = received_msg.data_length_code; - frame.user_data = SOCKETCAND_NORMAL_FRAME; - - enqueue_can_message(&frame, NULL); - } -} - -static void enqueue_can_message(socketcand_translate_frame_t *message, - const client_handler_data_t *skip_client_i) { - // send the message to all the tasks currently serving clients - for (int i = 0; i < MAX_CLIENTS; i++) { - if (&client_handler_datas[i] != skip_client_i && - client_handler_datas[i].tcp_messenger.socket_fd != -1) { - // append the message to the queue - if (xQueueSend(client_handler_datas[i].can_rx_queue, message, 0) != - pdTRUE) { - ESP_LOGE(TAG, "CAN bus task receive queue %d full. Dropping message.", - i); - } - } - } -} - static void delete_serve_client_task( client_handler_data_t *client_handler_data) { - xSemaphoreTake(client_handler_data->handler_task_delete_mutex, portMAX_DELAY); + // Enter the critical section. + assert(xSemaphoreTake(client_handler_data->handler_task_delete_mutex, + portMAX_DELAY) == pdTRUE); // If socket_fd hasn't already been set to -1, that means // I'm the first task to notice the client disconnected. @@ -536,28 +521,22 @@ static void delete_serve_client_task( close(client_handler_data->tcp_messenger.socket_fd); client_handler_data->tcp_messenger.socket_fd = -1; - // Send an interrupt frame to `can_rx_queue` so if the other task + // Send a `termination_msg` to `can_rx_queue` so if the other task // is blocking on receiving `can_rx_queue`, it knows to stop. - socketcand_translate_frame_t termination_frame; - termination_frame.user_data = SOCKETCAND_INTERRUPT_FRAME; - xQueueSend(client_handler_data->can_rx_queue, &termination_frame, 0); + twai_message_t termination_msg = {0}; + termination_msg.data_length_code = CAN_INTERRUPT_FRAME; + xQueueSend(client_handler_data->can_rx_queue, &termination_msg, 0); } else { - // Else, the other task has already disconnected the client. - // Now I'll just return the `client_handler_data` back to the - // `unused_client_handler_data_queue`. - BaseType_t res = - xQueueSend(unused_client_handler_data_queue, &client_handler_data, 0); - if (res != pdTRUE) { - ESP_LOGE( - TAG, - "Unreachable. Couldn't return client_handler_data to unused queue."); - abort(); - } + // Else, the other task has already disconnected from the client. + // Free this client handler data. + free_client_handler_data(client_handler_data); + ESP_LOGI(TAG, "Socketcand client disconnected."); } - xSemaphoreGive(client_handler_data->handler_task_delete_mutex); + assert(xSemaphoreGive(client_handler_data->handler_task_delete_mutex) == + pdTRUE); vTaskDelete(NULL); return; diff --git a/main/socketcand_server.h b/main/socketcand_server.h index a49d735..2acfa6a 100644 --- a/main/socketcand_server.h +++ b/main/socketcand_server.h @@ -2,20 +2,22 @@ #include "esp_err.h" +// The status of the socketcand server. +// Get the current status using `socketcand_server_status()`. typedef struct { uint64_t socketcand_frames_received; uint64_t socketcand_frames_sent; uint64_t invalid_socketcand_frames_received; - uint64_t can_bus_frames_received; uint64_t can_bus_frames_sent; - uint64_t can_bus_frames_send_fails; + uint64_t can_bus_frames_send_timeouts; } socketcand_server_status_t; -// Starts a socketcand TCP server listening on IPv4 `0.0.0.0:port` on a new +// Starts a socketcand TCP server listening on IPv4 `0.0.0.0:29536` on a new // task. Accepts up to 5 simultaneous TCP connections. // Must only be called one time. -esp_err_t socketcand_server_start(uint16_t port); +// Must be called after `can_listener` has been started. +esp_err_t socketcand_server_start(void); -// Returns the current `socketcand_server_status_t`. +// Fills `status_out` with the current `socketcand_server_status_t`. // Returns an error if the server isn't running. esp_err_t socketcand_server_status(socketcand_server_status_t* status_out); \ No newline at end of file diff --git a/main/socketcand_translate.c b/main/socketcand_translate.c index e61dfc1..1d0d7cc 100644 --- a/main/socketcand_translate.c +++ b/main/socketcand_translate.c @@ -9,11 +9,11 @@ static const char *TAG = "socketcand_server"; // See: https://en.wikipedia.org/wiki/CAN_bus#Frames #define CAN_SHORT_ID_MASK 0x000007FFU -esp_err_t socketcand_translate_frame_to_string( - char *buf, size_t bufsize, const socketcand_translate_frame_t *can_frame, - uint32_t secs, uint32_t usecs) { +esp_err_t socketcand_translate_frame_to_string(char *buf, size_t bufsize, + const twai_message_t *can_frame, + uint32_t secs, uint32_t usecs) { // Can't write more than 8 bytes to classic CAN payload - if (can_frame->len > 8) { + if (can_frame->data_length_code > 8) { ESP_LOGE(TAG, "Can't write more than 8 bytes in classic CAN payload."); return ESP_ERR_NO_MEM; } @@ -21,7 +21,7 @@ esp_err_t socketcand_translate_frame_to_string( int written = 0; int res = snprintf(buf + written, bufsize - written, "< frame %lX %ld.%ld ", - can_frame->id, secs, usecs); + can_frame->identifier, secs, usecs); written += res; if (res < 0 || written >= bufsize) { @@ -29,7 +29,7 @@ esp_err_t socketcand_translate_frame_to_string( } // Convert each byte to hex - for (int i = 0; i < can_frame->len; i++) { + for (int i = 0; i < can_frame->data_length_code; i++) { res = snprintf(buf + written, bufsize - written, "%02X", can_frame->data[i]); written += res; @@ -48,27 +48,38 @@ esp_err_t socketcand_translate_frame_to_string( return ESP_OK; } -esp_err_t socketcand_translate_string_to_frame( - const char *buf, socketcand_translate_frame_t *msg) { +esp_err_t socketcand_translate_string_to_frame(const char *buf, + twai_message_t *msg) { + // Set unused fields to zero + msg->rtr = 0; + msg->ss = 0; + msg->self = 0; + msg->dlc_non_comp = 0; + msg->reserved = 0; + // if this frame isn't a send frame - if (strncmp("< send ", buf, 7 != 0)) { + if (strncmp("< send ", buf, 7) != 0) { ESP_LOGE(TAG, "Invalid syntax in received socketcand frame."); return ESP_FAIL; } int count = sscanf(buf, "< send %lx %hhu %hhx %hhx %hhx %hhx %hhx %hhx %hhx %hhx >", - &(msg->id), &(msg->len), &msg->data[0], &msg->data[1], - &msg->data[2], &msg->data[3], &msg->data[4], &msg->data[5], - &msg->data[6], &msg->data[7]); + &(msg->identifier), &(msg->data_length_code), &msg->data[0], + &msg->data[1], &msg->data[2], &msg->data[3], &msg->data[4], + &msg->data[5], &msg->data[6], &msg->data[7]); - if ((count < 2) || (msg->len > 8) || (count != 2 + msg->len)) { + // Validate the frame syntax. + if ((count < 2) || (msg->data_length_code > 8) || + (count != 2 + msg->data_length_code)) { ESP_LOGE(TAG, "Invalid syntax in received socketcand frame."); + return ESP_FAIL; } - if (msg->id > CAN_SHORT_ID_MASK) { - msg->ext = 1; + + if (msg->identifier > CAN_SHORT_ID_MASK) { + msg->extd = 1; } else { - msg->ext = 0; + msg->extd = 0; } return ESP_OK; diff --git a/main/socketcand_translate.h b/main/socketcand_translate.h index 14e420b..7ce0ba5 100644 --- a/main/socketcand_translate.h +++ b/main/socketcand_translate.h @@ -5,6 +5,7 @@ #include #include #include +#include "driver/twai.h" #include "esp_err.h" @@ -18,27 +19,12 @@ // enough to hold all socketcand `send` and `frame` message strings. #define SOCKETCAND_RAW_MAX_LEN 64 -// A CAN frame -typedef struct { - // CAN Frame ID - uint32_t id; - // Length of `data` - uint8_t len; - // CAN frame payload - uint8_t data[8]; - // Is the ID extended? - bool ext; - // Unused field. - // The user may freely use it however they want. - uint8_t user_data; -} socketcand_translate_frame_t; - // Translates a `socketcand_translate_frame_t` to a socketcand string of form `< // frame can_id seconds.useconds [data]* >`. // Returns `ESP_ERR_NO_MEM` if `bufsize` is too small too fit the string. // https://github.com/linux-can/socketcand/blob/master/doc/protocol.md esp_err_t socketcand_translate_frame_to_string( - char *buf, size_t bufsize, const socketcand_translate_frame_t *can_frame, + char *buf, size_t bufsize, const twai_message_t *can_frame, uint32_t secs, uint32_t usecs); // Translates a null-terminated @@ -46,7 +32,7 @@ esp_err_t socketcand_translate_frame_to_string( // `socketcand_translate_frame_t`. // Returns `ESP_FAIL` if `buf` has an invalid socketcand syntax. esp_err_t socketcand_translate_string_to_frame( - const char *buf, socketcand_translate_frame_t *msg); + const char *buf, twai_message_t *msg); // This function is used to mimic the socketcand protocol // for opening a rawmode connection. diff --git a/main/status_report.c b/main/status_report.c index 7511f41..f9b8983 100644 --- a/main/status_report.c +++ b/main/status_report.c @@ -1,5 +1,7 @@ #include "status_report.h" +#include "can_listener.h" +#include "cyphal_node.h" #include "driver/twai.h" #include "esp_check.h" #include "esp_netif_types.h" @@ -9,25 +11,31 @@ #include "string.h" // Name that will be used for logging -static const char *TAG = "socketcand_server"; +static const char *TAG = "status_report"; -// Prints the status of `netif` to `buf` in JSON format. +// Prints the status of `netif` to `buf_out` in JSON format. // Returns an error if `buflen` was too small. // Increments `bytes_written` by the number of bytes written. static esp_err_t print_netif_status(esp_netif_t *netif, char *buf_out, size_t buflen, size_t *bytes_written); -// Prints the status of the CAN bus to `buf` in JSON format. +// Prints the status of the CAN bus to `buf_out` in JSON format. // Returns an error if `buflen` was too small. // Increments `bytes_written` by the number of bytes written. static esp_err_t print_can_status(char *buf_out, size_t buflen, size_t *bytes_written); -// Prints the status of socketcand to `buf` in JSON format. +// Prints the status of socketcand to `buf_out` in JSON format. // Returns an error if `buflen` was too small. // Increments `bytes_written` by the number of bytes written. -static esp_err_t print_socketcand_status(char *buf_out, size_t buflen, - size_t *bytes_written); +static esp_err_t print_application_status(char *buf_out, size_t buflen, + size_t *bytes_written); + +// Prints the status of the `cyphal_node` to `buf_out` in JSON format. +// Returns an error if `buflen` was too small. +// Increments `bytes_written` by the number of bytes written. +static esp_err_t print_cyphal_status(char *buf_out, size_t buflen, + size_t *bytes_written); static char status_json[2048]; static SemaphoreHandle_t status_json_mutex = NULL; @@ -38,7 +46,7 @@ esp_err_t status_report_get(const char **json_out, esp_netif_t *eth_netif, if (status_json_mutex == NULL) { status_json_mutex = xSemaphoreCreateMutexStatic(&status_json_mutex_mem); } - xSemaphoreTake(status_json_mutex, portMAX_DELAY); + assert(xSemaphoreTake(status_json_mutex, portMAX_DELAY) == pdTRUE); esp_err_t err; int res; @@ -86,7 +94,7 @@ esp_err_t status_report_get(const char **json_out, esp_netif_t *eth_netif, // Print the CAN bus status res = snprintf(status_json + written, sizeof(status_json) - written, ",\n" - "\"CAN Bus status\": "); + "\"CAN Driver status\": "); written += res; if (res < 0 || written >= sizeof(status_json)) { ESP_LOGE(TAG, "driver_setup_get_status_json() buflen too small."); @@ -100,22 +108,36 @@ esp_err_t status_report_get(const char **json_out, esp_netif_t *eth_netif, // Print the Socketcand status res = snprintf(status_json + written, sizeof(status_json) - written, ",\n" - "\"Socketcand adapter status\": "); + "\"Application status\": "); written += res; if (res < 0 || written >= sizeof(status_json)) { ESP_LOGE(TAG, "driver_setup_get_status_json() buflen too small."); return ESP_ERR_NO_MEM; } - res = print_socketcand_status(status_json + written, - sizeof(status_json) - written, &written); + // Print the application status + res = print_application_status(status_json + written, + sizeof(status_json) - written, &written); ESP_RETURN_ON_ERROR(err, TAG, "Couldn't print socketcand status."); + res = snprintf(status_json + written, sizeof(status_json) - written, + ",\n" + "\"OpenCyphal Node status\": "); + written += res; + if (res < 0 || written >= sizeof(status_json)) { + ESP_LOGE(TAG, "driver_setup_get_status_json() buflen too small."); + return ESP_ERR_NO_MEM; + } + + // Print the OpenCyphal status + res = print_cyphal_status(status_json + written, + sizeof(status_json) - written, &written); + ESP_RETURN_ON_ERROR(err, TAG, "Couldn't print OpenCyphal status."); + res = snprintf(status_json + written, sizeof(status_json) - written, "\n" "}\n"); written += res; - if (res < 0 || written >= sizeof(status_json)) { ESP_LOGE(TAG, "driver_setup_get_status_json() buflen too small."); return ESP_ERR_NO_MEM; @@ -129,12 +151,10 @@ esp_err_t status_report_release() { if (status_json_mutex == NULL) { return ESP_FAIL; } - if (xSemaphoreGive(status_json_mutex) != pdTRUE) { - ESP_LOGE(TAG, "Error releasing driver setup JSON status mutex."); - return ESP_FAIL; - } else { - return ESP_OK; - } + + assert(xSemaphoreGive(status_json_mutex) == pdTRUE); + + return ESP_OK; } static esp_err_t print_netif_status(esp_netif_t *netif, char *buf_out, @@ -269,7 +289,7 @@ static esp_err_t print_can_status(char *buf_out, size_t buflen, "\"Total number of failed message transmissions\": " "%ld,\n" - "\"Total number of missed message receptions\": " + "\"Total number of failed message receptions\": " "%ld,\n" "\"Total number of incoming messages lost due to FIFO overrun\": " @@ -297,11 +317,34 @@ static esp_err_t print_can_status(char *buf_out, size_t buflen, return ESP_OK; } -static esp_err_t print_socketcand_status(char *buf_out, size_t buflen, - size_t *bytes_written) { - socketcand_server_status_t status; - esp_err_t err = socketcand_server_status(&status); - ESP_RETURN_ON_ERROR(err, TAG, "Couldn't get socketcand server status."); +static esp_err_t print_application_status(char *buf_out, size_t buflen, + size_t *bytes_written) { + socketcand_server_status_t socketcand_status; + esp_err_t err = socketcand_server_status(&socketcand_status); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Couldn't get socketcand server status: %s", + esp_err_to_name(err)); + int written = snprintf(buf_out, buflen, "\"Not running\""); + if (written < 0 || written >= buflen) { + ESP_LOGE(TAG, "print_application_status buflen too short."); + return ESP_ERR_NO_MEM; + } + *bytes_written += written; + return ESP_OK; + } + + can_listener_status_t can_listener_status; + err = can_listener_get_status(&can_listener_status); + if (err != ESP_OK) { + ESP_LOGE(TAG, "Couldn't get CAN listener status: %s", esp_err_to_name(err)); + int written = snprintf(buf_out, buflen, "\"Not running\""); + if (written < 0 || written >= buflen) { + ESP_LOGE(TAG, "print_application_status buflen too short."); + return ESP_ERR_NO_MEM; + } + *bytes_written += written; + return ESP_OK; + } int written = snprintf(buf_out, buflen, @@ -313,26 +356,72 @@ static esp_err_t print_socketcand_status(char *buf_out, size_t buflen, "\"Total invalid socketcand frames received over TCP\": " "%lld,\n" - "\"Total frames transmitted to CAN bus\": " + "\"Total frames from socketcand transmitted to CAN bus\": " "%lld,\n" - "\"Total CAN transmit fails\": " + "\"Total frames from socketcand that timed out while being transmitted to CAN bus\": " "%lld,\n" "\"Total frames received from CAN bus\": " "%lld,\n" + "\"Total received CAN frames dropped\": " + "%lld,\n" + "\"Total socketcand frames sent over TCP\": " "%lld\n" "}", - status.socketcand_frames_received, - status.invalid_socketcand_frames_received, - status.can_bus_frames_sent, status.can_bus_frames_send_fails, - status.can_bus_frames_received, status.socketcand_frames_sent); + socketcand_status.socketcand_frames_received, + socketcand_status.invalid_socketcand_frames_received, + socketcand_status.can_bus_frames_sent, + socketcand_status.can_bus_frames_send_timeouts, + can_listener_status.can_bus_frames_received, + can_listener_status.can_bus_incoming_frames_dropped, + socketcand_status.socketcand_frames_sent); if (written < 0 || written >= buflen) { - ESP_LOGE(TAG, "print_netif_status buflen too short."); + ESP_LOGE(TAG, "print_application_status buflen too short."); + return ESP_ERR_NO_MEM; + } + + *bytes_written += written; + return ESP_OK; +} + +static esp_err_t print_cyphal_status(char *buf_out, size_t buflen, + size_t *bytes_written) { + + cyphal_node_status_t cyphal_status; + esp_err_t err = cyphal_node_get_status(&cyphal_status); + if (err != ESP_OK) { + int written = snprintf(buf_out, buflen, "\"Not running\""); + if (written < 0 || written >= buflen) { + ESP_LOGE(TAG, "print_application_status buflen too short."); + return ESP_ERR_NO_MEM; + } + *bytes_written += written; + + return ESP_OK; + } + + int written = + snprintf(buf_out, buflen, + "{\n" + + "\"Total OpenCyphal heartbeats sent\": " + "%lld,\n" + + "\"Total OpenCyphal heartbeats received\": " + "%lld\n" + + "}", + cyphal_status.heartbeats_sent, + cyphal_status.heartbeats_received + ); + + if (written < 0 || written >= buflen) { + ESP_LOGE(TAG, "print_cyphal_status buflen too short."); return ESP_ERR_NO_MEM; } diff --git a/main/status_report.h b/main/status_report.h index 53b4e02..ea2cff0 100644 --- a/main/status_report.h +++ b/main/status_report.h @@ -13,11 +13,11 @@ // this function will block if another task is also // currently reading the status. // Once the caller is done reading the string, -// they must call `driver_setup_release_json_status()` to +// they must call `status_report_release()` to // allow other callers to access the status. esp_err_t status_report_get(const char** json_out, esp_netif_t* eth_netif, esp_netif_t* wifi_netif); // Must be called once finished reading the buffer -// returned by `driver_setup_get_status_json()`. +// returned by `status_report_get()`. esp_err_t status_report_release(void); \ No newline at end of file diff --git a/main/website/index.html b/main/website/index.html index d937e3d..2350fda 100644 --- a/main/website/index.html +++ b/main/website/index.html @@ -83,7 +83,7 @@

ESP32 Socketcand Adapter

-

Network Settings

+

Settings

The current configuration is in the input fields. Change anything, and click submit to save the settings and reboot the adapter. @@ -108,7 +108,16 @@

Network Settings

@@ -186,7 +195,16 @@

Network Settings

@@ -248,7 +266,39 @@

Network Settings

+ + + + + + + + + + + + + + + + + + +