diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..620763f --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "lib/libcanard"] + path = lib/libcanard + url = git@git.nilsschulte.de:nils/libcanard.git diff --git a/CMakeLists.txt b/CMakeLists.txt index 87f1210..c1138c1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,32 +1,41 @@ cmake_minimum_required(VERSION 3.16) -project(cyphal_hardware_interface LANGUAGES CXX) +project(cyphal_hardware_interface LANGUAGES C CXX) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") add_compile_options(-Wall -Wextra) endif() +enable_language(C CXX) + # find dependencies set(THIS_PACKAGE_INCLUDE_DEPENDS - hardware_interface - pluginlib - rclcpp - rclcpp_lifecycle + hardware_interface::hardware_interface + hardware_interface::mock_components + pluginlib::pluginlib + rclcpp::rclcpp + #rclcpp_lifecycle::rclcpp_lifecycle ) # find dependencies find_package(ament_cmake REQUIRED) -foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) - find_package(${Dependency} REQUIRED) -endforeach() +find_package(hardware_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +#find_package(rclcpp_lifecycle REQUIRED) -# find_package(cyphal) -# message(${cyphal_INCLUDE_DIR}) -## COMPILE add_library( cyphal_hardware_interface SHARED hardware/cyphal_system.cpp + hardware/socketcan.cpp + lib/libcanard/libcanard/canard.c + #hardware/canard.c +) + +target_include_directories(cyphal_hardware_interface + PRIVATE + lib/libcanard/libcanard/ ) function(get_all_targets var) @@ -45,15 +54,19 @@ macro(get_all_targets_recursive targets dir) list(APPEND ${targets} ${current_targets}) endmacro() -target_compile_features(cyphal_hardware_interface PUBLIC cxx_std_17) +target_compile_features(cyphal_hardware_interface PUBLIC cxx_std_20) target_include_directories(cyphal_hardware_interface PUBLIC $ $ ${cyphal_INCLUDE_DIR} ) -ament_target_dependencies( - cyphal_hardware_interface PUBLIC - ${THIS_PACKAGE_INCLUDE_DEPENDS} + +target_link_libraries(cyphal_hardware_interface PUBLIC + hardware_interface::hardware_interface + hardware_interface::mock_components + pluginlib::pluginlib + rclcpp::rclcpp + #rclcpp_lifecycle::rclcpp_lifecycyle ) # Causes the visibility macros to use dllexport rather than dllimport, diff --git a/bringup/config/staubi_controllers.yaml b/bringup/config/staubi_controllers.yaml index 3415db2..ad2073e 100644 --- a/bringup/config/staubi_controllers.yaml +++ b/bringup/config/staubi_controllers.yaml @@ -8,18 +8,6 @@ controller_manager: staubi_base_controller: type: diff_drive_controller/DiffDriveController - vacuum_controller: - # type: forward_command_controller/ForwardCommandController - type: joy_forward_controller/JoyForwardController - -vacuum_controller: - ros__parameters: - joints: - - vacuum - interface_name: power - button_number: 9 - button_toggle: true - staubi_base_controller: ros__parameters: left_wheel_names: ["left_wheel_joint"] diff --git a/bringup/launch/staubi.launch.py b/bringup/launch/staubi.launch.py index 1f39456..57e4fa1 100644 --- a/bringup/launch/staubi.launch.py +++ b/bringup/launch/staubi.launch.py @@ -34,7 +34,7 @@ def generate_launch_description(): declared_arguments.append( DeclareLaunchArgument( "joy", - default_value="true", + default_value="false", description="Start joy node with this launch file.", ) ) @@ -142,9 +142,9 @@ def generate_launch_description(): parameters=[robot_description, robot_controllers], output="both", remappings=[ - ("/vacuum_controller/joy", "/joy"), ("/staubi_base_controller/cmd_vel", "/cmd_vel_nav"), ], + #prefix=['gdbserver localhost:3000'], ) robot_state_pub_node = Node( package="robot_state_publisher", @@ -176,12 +176,6 @@ def generate_launch_description(): arguments=["staubi_base_controller", "--controller-manager", "/controller_manager"], ) - vacuum_controller_spawner = Node( - package="controller_manager", - executable="spawner", - arguments=["vacuum_controller", "--controller-manager", "/controller_manager"], - ) - # Delay rviz start after `joint_state_broadcaster` delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler( event_handler=OnProcessExit( @@ -197,15 +191,6 @@ def generate_launch_description(): on_exit=[robot_controller_spawner], ) ) - - delay_vacuum_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler( - event_handler=OnProcessExit( - target_action=joint_state_broadcaster_spawner, - on_exit=[vacuum_controller_spawner], - ) - ) - - joy_ld = [ DeclareLaunchArgument('joy_vel', default_value='/cmd_vel_nav'), @@ -247,7 +232,6 @@ def generate_launch_description(): joint_state_broadcaster_spawner, delay_rviz_after_joint_state_broadcaster_spawner, delay_robot_controller_spawner_after_joint_state_broadcaster_spawner, - delay_vacuum_controller_spawner_after_joint_state_broadcaster_spawner, - ] + joy_ld + lidar_ld + ] + joy_ld #+ lidar_ld return LaunchDescription(declared_arguments + nodes) diff --git a/description/ros2_control/staubi.ros2_control.xacro b/description/ros2_control/staubi.ros2_control.xacro index 4b09df6..98708ef 100644 --- a/description/ros2_control/staubi.ros2_control.xacro +++ b/description/ros2_control/staubi.ros2_control.xacro @@ -7,9 +7,9 @@ cyphal_hardware_interface/cyphalSystemHardware - /dev/ttyAMA10 + can0 - 460800 + @@ -19,24 +19,8 @@ true - - vcc - 0.001 - - - - s - 0.1427 - - 0 - 1 - - - vt0 - a0 - v0 - 0.0001 + 125 @@ -44,18 +28,13 @@ - - vt1 - a1 - v1 - 0.0001 + - + diff --git a/hardware/cyphal_system.cpp b/hardware/cyphal_system.cpp index 1eaf955..5e96042 100644 --- a/hardware/cyphal_system.cpp +++ b/hardware/cyphal_system.cpp @@ -1,3 +1,5 @@ +#define NUNAVUT_ASSERT assert +#include "include/cyphal_hardware_interface/cyphal_system.hpp" #include "cyphal_hardware_interface/cyphal_system.hpp" #include @@ -11,49 +13,205 @@ #include #include -//#include "serial.hpp" +#include + +#include "socketcan.h" + +// #include "serial.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp/rclcpp.hpp" -//#include "cyphal.hpp" +// #include "cyphal.hpp" +#include +#include +#include // For std::setw, std::setfill, std::hex, etc. +#include +#include // For std::ostringstream +#include + +#define NUNAVUT_ASSERT assert + +extern "C" { +#include "canard.h" +#include +#include +#include +#include +#include +} namespace cyphal_hardware_interface { +uint64_t getMonotonicMicroseconds() { + auto now = std::chrono::steady_clock::now(); + auto micros = std::chrono::duration_cast( + now.time_since_epoch()) + .count(); + return static_cast(micros); +} + +std::string cyphalUdralServo::get_non_read_register_name() const { + for (const auto &[name, reg] : registers) { + if (uavcan_register_Value_1_0_is_empty_(®)) { + return name; + } + } + return ""; +} + +bool cyphalUdralServo::all_registers_read() const { + return state.register_read && get_non_read_register_name() == ""; +} + cyphalSystemHardware::~cyphalSystemHardware() { - if (serial_port_handle) { + if (can_socket >= 0) { RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "Closing port '%s'", serial_port_.c_str()); - close(serial_port_handle); + "Closing socket of interface '%s'", can_if_.c_str()); + // close(serial_port_handle); } } +void cyphalSystemHardware::send(const CanardMicrosecond tx_deadline_usec, + const CanardTransferMetadata *const metadata, + const size_t payload_size, + const void *const payload_data, + const CanardMicrosecond now_usec) { + const struct CanardPayload payload = {.size = payload_size, + .data = payload_data}; + (void)canardTxPush(&canard_tx_queues[0], &canard, tx_deadline_usec, metadata, + payload, now_usec, NULL); +} + +void cyphalSystemHardware::read_register_list_idx(unsigned char node_id, + int register_idx) { + uavcan_register_List_Request_1_0 msg = {0}; + msg.index = register_idx; + const CanardMicrosecond now_usec = getMonotonicMicroseconds(); + uint8_t serialized + [uavcan_register_List_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_]; + size_t serialized_size = sizeof(serialized); + const int8_t err = uavcan_register_List_Request_1_0_serialize_( + &msg, &serialized[0], &serialized_size); + assert(err >= 0); + if (err >= 0) { + const CanardTransferMetadata transfer = { + .priority = CanardPriorityNominal, + .transfer_kind = CanardTransferKindRequest, + .port_id = uavcan_register_List_1_0_FIXED_PORT_ID_, + .remote_node_id = node_id, + .transfer_id = (CanardTransferID)(next_transfer_id++), + }; + send(now_usec + 1e9, &transfer, serialized_size, &serialized[0], now_usec); + } +} + +void cyphalSystemHardware::send_readyness(cyphalUdralServo &servo, enum arming_state arming_state_target) { + if (!servo.registers.contains("uavcan.sub.servo.readiness.id")) { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "port not found"); + return; + } + if (!uavcan_register_Value_1_0_is_natural16_( + &servo.registers["uavcan.sub.servo.readiness.id"])) { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "not natural16"); + return; + } + if (servo.registers["uavcan.sub.servo.readiness.id"].natural16.value.count != + 1) { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "servo.registers[\"uavcan.sub.servo.readiness.id\"].natural16.value.count == %d",(int) servo.registers["uavcan.sub.servo.readiness.id"].natural16.value.count ); + return; + } + + const uint16_t readiness_port = + servo.registers["uavcan.sub.servo.readiness.id"] + .natural16.value.elements[0]; + + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "sending readiness state to %d on port %d", (int)servo.node_id, (int)readiness_port); + reg_udral_service_common_Readiness_0_1 msg; + msg.value = arming_state_target == ARMED ? reg_udral_service_common_Readiness_0_1_ENGAGED : reg_udral_service_common_Readiness_0_1_STANDBY; + const CanardMicrosecond now_usec = getMonotonicMicroseconds(); + uint8_t serialized + [reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_]; + size_t serialized_size = sizeof(serialized); + const int8_t err = reg_udral_service_common_Readiness_0_1_serialize_( + &msg, &serialized[0], &serialized_size); + assert(err >= 0); + if (err >= 0) { + const CanardTransferMetadata transfer = { + .priority = CanardPriorityNominal, + //.transfer_kind = CanardTransferKindRequest, + .transfer_kind = CanardTransferKindMessage, + .port_id = readiness_port, + .remote_node_id = CANARD_NODE_ID_UNSET, + .transfer_id = (CanardTransferID)(next_transfer_id++), + }; + send(now_usec + 1e9, &transfer, serialized_size, &serialized[0], now_usec); + } +} + +void cyphalSystemHardware::read_register(cyphalUdralServo &servo, + std::string name) { + if (servo.state.requested_register_name != "" || name == "") { + return; + } + servo.state.requested_register_name = name; + unsigned char node_id = servo.node_id; + uavcan_register_Access_Request_1_0 msg; + memset(&msg, 0, sizeof msg); + if (name.length() > sizeof msg.name.name.elements - 1) { + name.resize(sizeof msg.name.name.elements); + } + strcpy((char *)msg.name.name.elements, name.c_str()); + msg.name.name.count = name.length(); + uavcan_register_Value_1_0_select_empty_(&msg.value); + const CanardMicrosecond now_usec = getMonotonicMicroseconds(); + uint8_t serialized + [uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_]; + size_t serialized_size = sizeof(serialized); + const int8_t err = uavcan_register_Access_Request_1_0_serialize_( + &msg, &serialized[0], &serialized_size); + assert(err >= 0); + if (err >= 0) { + const CanardTransferMetadata transfer = { + .priority = CanardPriorityNominal, + .transfer_kind = CanardTransferKindRequest, + .port_id = uavcan_register_Access_1_0_FIXED_PORT_ID_, + .remote_node_id = node_id, + .transfer_id = (CanardTransferID)(next_transfer_id++), + }; + send(now_usec + 1e9, &transfer, serialized_size, &serialized[0], now_usec); + } +} + +/** + * @brief Static method to call read_thread via std::thread + * @param context pointer to this + */ +void cyphalSystemHardware::read_thread_static(void *context) { + static_cast(context)->read_thread(); +} + hardware_interface::CallbackReturn cyphalSystemHardware::on_init( - const hardware_interface::HardwareInfo &info) { - if (hardware_interface::SystemInterface::on_init(info) != + const hardware_interface::HardwareComponentInterfaceParams ¶ms) { + if (hardware_interface::SystemInterface::on_init(params) != hardware_interface::CallbackReturn::SUCCESS) { return hardware_interface::CallbackReturn::ERROR; } - serial_port_ = default_serial_port_; + can_if_ = default_if_; - if (info_.hardware_parameters.count("port") > 0) { - serial_port_ = info_.hardware_parameters.at("port"); + if (info_.hardware_parameters.count("can_if") > 0) { + can_if_ = info_.hardware_parameters.at("can_if"); } else { RCLCPP_WARN(rclcpp::get_logger("cyphalSystemHardware"), - "No port specified in urdf, using default value"); + "No can interface specified in urdf, using default value"); } - if (info_.hardware_parameters.count("try_next_port_number") > 0) { - std::string try_next_str = - info_.hardware_parameters.at("try_next_port_number"); - try_next_port_number = - std::set({"True", "true", "1", "Yes", "yes", "Y", "y"}) - .count(try_next_str) > 0; - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "Trying next ports if the one provided is not openable"); - } - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "Port set as %s", - serial_port_.c_str()); + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "If set as %s", + can_if_.c_str()); std::vector components; components.insert(components.begin(), info_.joints.begin(), @@ -61,181 +219,341 @@ hardware_interface::CallbackReturn cyphalSystemHardware::on_init( components.insert(components.begin(), info_.sensors.begin(), info_.sensors.end()); components.insert(components.begin(), info_.gpios.begin(), info_.gpios.end()); - for (const hardware_interface::ComponentInfo &joint : components) { - // StaubiSystem has exactly two states and one command interface on each - // joint - /*if (joint.command_interfaces.size() != 1) { - RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), - "Joint '%s' has %zu command interfaces found. 1 expected.", - joint.name.c_str(), joint.command_interfaces.size()); - return hardware_interface::CallbackReturn::ERROR; - }*/ - for (const auto &i : joint.command_interfaces) { - std::string param_name = "command:" + i.name; - if (joint.parameters.count(param_name) <= 0) { - RCLCPP_FATAL( - rclcpp::get_logger("cyphalSystemHardware"), - "command interface '%s' of joint/gpio '%s' has no parameter " - "'command:%s'.", - i.name.c_str(), joint.name.c_str(), i.name.c_str()); - return hardware_interface::CallbackReturn::ERROR; - } - auto interface_name = joint.parameters.at(param_name); - if (interfaces_map.count(interface_name) > 0) { - RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), - "Sync Interface '%s' used twice. FATAL ERROR.", - interface_name.c_str()); - return hardware_interface::CallbackReturn::ERROR; - } - interfaces_map[interface_name] = { - std::numeric_limits::quiet_NaN(), - (joint.parameters.count("factor") > 0) - ? std::stod(joint.parameters.at("factor")) - : 1.0, - joint.name, true, i.name}; - } - for (const auto &i : joint.state_interfaces) { - std::string param_name = "state:" + i.name; - if (joint.parameters.count(param_name) <= 0) { - RCLCPP_FATAL( - rclcpp::get_logger("cyphalSystemHardware"), - "state interface '%s' of joint/sensor/gpio '%s' has no parameter " - "'state:%s'.", - i.name.c_str(), joint.name.c_str(), i.name.c_str()); + for (const hardware_interface::ComponentInfo &joint : components) { + if (joint.parameters.contains("node_id")) { + int node_id = -1; + try { + node_id = std::stoi(joint.parameters.at("node_id")); + } catch (std::exception &e) { + } + if (node_id < 0 || node_id >= 0xFF) { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "No node_id '%s' invalid!", + joint.parameters.at("node_id").c_str()); return hardware_interface::CallbackReturn::ERROR; } - auto interface_name = joint.parameters.at(param_name); - if (interfaces_map.count(interface_name) > 0) { - RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), - "Sync Interface '%s' used twice. FATAL ERROR.", - interface_name.c_str()); - return hardware_interface::CallbackReturn::ERROR; - } - interfaces_map[interface_name] = { - std::numeric_limits::quiet_NaN(), - (joint.parameters.count("factor") > 0) - ? std::stod(joint.parameters.at("factor")) - : 1.0, - joint.name, false, i.name}; + servos[node_id].node_id = node_id; + } else { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "No node_id configured for servo!"); + return hardware_interface::CallbackReturn::ERROR; } + // for (const auto &i : joint.command_interfaces) { + // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "%s: %s: %d", + // joint.name.c_str(), i.name.c_str(), + // (int)i.parameters.size()); + // } + // for (const auto &i : joint.state_interfaces) { + // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "%s: %s: %d", + // joint.name.c_str(), i.name.c_str(), + // (int)i.parameters.size()); + // } + } + + canard_memory.deallocate = canardDeallocate; + canard_memory.allocate = canardAllocate; + + // The libcanard instance requires the allocator for managing protocol states. + canard = canardInit(canard_memory); + + canard_tx_queues[0] = + canardTxInit(100, CANARD_MTU_CAN_CLASSIC, canard_memory); + canard.node_id = 100; + + static struct CanardRxSubscription rx; + int8_t res = // + canardRxSubscribe(&canard, CanardTransferKindMessage, + uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_, + uavcan_node_Heartbeat_1_0_EXTENT_BYTES_, + CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, &rx); + if (res < 0) { + return hardware_interface::CallbackReturn::ERROR; + } + + static struct CanardRxSubscription rx_register_list_response_; + res = // + canardRxSubscribe(&canard, CanardTransferKindResponse, + uavcan_register_List_1_0_FIXED_PORT_ID_, + uavcan_register_List_Response_1_0_EXTENT_BYTES_, + CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, + &rx_register_list_response_); + if (res < 0) { + return hardware_interface::CallbackReturn::ERROR; + } + + static struct CanardRxSubscription rx_register_access_Response_; + res = // + canardRxSubscribe(&canard, CanardTransferKindResponse, + uavcan_register_Access_1_0_FIXED_PORT_ID_, + uavcan_register_Access_Response_1_0_EXTENT_BYTES_, + CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, + &rx_register_access_Response_); + if (res < 0) { + return hardware_interface::CallbackReturn::ERROR; } - // for (const auto &[key, value] : interfaces_map) { - // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // "Interface %s added (factor: %f).", key.c_str(), value.factor); - // } return hardware_interface::CallbackReturn::SUCCESS; } // namespace cyphal_hardware_interface -std::vector -cyphalSystemHardware::export_state_interfaces() { - std::vector state_interfaces; - for (auto &[key, value] : interfaces_map) { - if (!value.command) - state_interfaces.emplace_back(hardware_interface::StateInterface( - value.joint, value.control_interface, &value.value)); - } - /* for (auto i = 0u; i < info_.joints.size(); i++) { - state_interfaces.emplace_back(hardware_interface::StateInterface( - info_.joints[i].name, hardware_interface::HW_IF_POSITION, - &hw_positions_[i])); - state_interfaces.emplace_back(hardware_interface::StateInterface( - info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, - &hw_velocities_[i])); - } - */ - return state_interfaces; -} - -std::vector -cyphalSystemHardware::export_command_interfaces() { - std::vector command_interfaces; - for (auto &[key, value] : interfaces_map) { - if (value.command) - command_interfaces.emplace_back(hardware_interface::CommandInterface( - value.joint, value.control_interface, &value.value)); - } - /* for (auto i = 0u; i < info_.joints.size(); i++) { - command_interfaces.emplace_back(hardware_interface::CommandInterface( - info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, - &hw_commands_[i])); - } - */ - return command_interfaces; -} - hardware_interface::CallbackReturn cyphalSystemHardware::on_configure( const rclcpp_lifecycle::State & /*previous_state*/) { - // const hardware_interface::CallbackReturn result = - // can_interface_->connect(can_socket_) - // ? hardware_interface::CallbackReturn::SUCCESS - // : hardware_interface::CallbackReturn::FAILURE; - // Open the serial port. Change device path as needed (currently set to an - // standard FTDI USB-UART cable type device) - // serial_port_handle = open_serial(serial_port_); - // if (!serial_port_handle) { - // RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), - // "Error opening port '%s': %s", serial_port_.c_str(), - // strerror(errno)); - // if (try_next_port_number) { - // for (unsigned int tries = 0; tries < 100; tries += 1) { - // size_t digits_idx = serial_port_.size() - 1; - // while (digits_idx > 0 && std::isdigit(serial_port_[digits_idx])) - // digits_idx -= 1; - // digits_idx += 1; - // std::string number_str = serial_port_.substr(digits_idx); - // unsigned int number = number_str.size() > 0 ? std::stol(number_str) : 0; - // serial_port_ = - // serial_port_.substr(0, digits_idx) + std::to_string(number + 1); - // serial_port_handle = open_serial(serial_port_); - // if (!serial_port_handle) { - // RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), - // "Error opening port '%s': %s", serial_port_.c_str(), - // strerror(errno)); - // } else - // break; - // } - // } - // if (!serial_port_handle) - // return hardware_interface::CallbackReturn::FAILURE; - // } - // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // "Successfuly opened port '%s'", serial_port_.c_str()); + can_socket = socketcanOpen(can_if_.c_str(), 8); /* MTU == 8 -> classic CAN */ + if (can_socket < 0) { + RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), + "Could not open socket for can interface '%s'", + can_if_.c_str()); + return hardware_interface::CallbackReturn::FAILURE; + } + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "Opened socketcan socket for '%s'", can_if_.c_str()); + read_thread_handle = std::thread([this]() { read_thread_static(this); }); + + /** wait_for_nodes **/ + using namespace std::chrono_literals; + auto start_time = std::chrono::steady_clock::now(); + while (true) { + bool ready = true; + for (const auto &[id, s] : servos) { + std::unique_lock lock{s.mtx}; + if (!s.state.alive || !s.all_registers_read()) { + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "Waiting for '%d'", id); + ready = false; + break; + } + } + if (ready) { + break; + } + if (std::chrono::steady_clock::now() > start_time + 10000ms) { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "Timed out while waiting for servos"); + return hardware_interface::CallbackReturn::ERROR; + } + std::this_thread::sleep_for(200ms); + } + + // read_register_list_idx(125, 1); return hardware_interface::CallbackReturn::SUCCESS; } +void cyphalSystemHardware::processReceivedTransfer( + const struct CanardRxTransfer *const transfer, + const CanardMicrosecond now_usec) { + (void)now_usec; + const int node_id = transfer->metadata.remote_node_id; + if (transfer->metadata.transfer_kind == CanardTransferKindResponse) { + if (!servos.contains(node_id)) { + return; + } + std::unique_lock lock{servos[node_id].mtx}; + if (transfer->metadata.port_id == uavcan_register_List_1_0_FIXED_PORT_ID_) { + + uavcan_register_List_Response_1_0 resp; + memset(&resp, 0, sizeof resp); + size_t size = transfer->payload.size; + + if (uavcan_register_List_Response_1_0_deserialize_( + &resp, (uint8_t *)transfer->payload.data, &size) >= 0) { + if (resp.name.name.count == 0) { + + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "Register list read from '%d'", node_id); + servos[node_id].state.register_read = true; + read_register(servos[node_id], + servos[node_id].get_non_read_register_name()); + } else { + char name[uavcan_register_Name_1_0_name_ARRAY_CAPACITY_ + 1] = {0}; + memcpy(&name[0], resp.name.name.elements, resp.name.name.count); + name[resp.name.name.count] = '\0'; + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "reg_name: %s", name); + uavcan_register_Value_1_0 value; + uavcan_register_Value_1_0_select_empty_(&value); + servos[node_id].registers[name] = value; + read_register_list_idx(node_id, servos[node_id].registers.size()); + } + } + } else if (transfer->metadata.port_id == + uavcan_register_Access_1_0_FIXED_PORT_ID_) { + uavcan_register_Access_Response_1_0 resp; + memset(&resp, 0, sizeof resp); + size_t size = transfer->payload.size; + if (uavcan_register_Access_Response_1_0_deserialize_( + &resp, (uint8_t *)transfer->payload.data, &size) >= 0) { + if (servos[node_id].state.requested_register_name.length() == 0) { + RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"), + "reg_value recieved but non requested!"); + return; + } + servos[node_id] + .registers[servos[node_id].state.requested_register_name] = + resp.value; + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "reg_value '%s' recieved", + servos[node_id].state.requested_register_name.c_str()); + servos[node_id].state.requested_register_name = ""; + if (servos[node_id].state.requested_register_name == "") { + auto non_read_register = servos[node_id].get_non_read_register_name(); + read_register(servos[node_id], non_read_register); + } + } + } + } else if (transfer->metadata.transfer_kind == CanardTransferKindMessage) { + if (transfer->metadata.port_id == + uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_) { + + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "heartbeat of '%d' recieved", node_id); + if (!servos.contains(node_id)) { + return; + } + std::unique_lock lock{servos[node_id].mtx}; + uavcan_node_Heartbeat_1_0 msg; + size_t size = transfer->payload.size; + if (uavcan_node_Heartbeat_1_0_deserialize_( + &msg, (uint8_t *)transfer->payload.data, &size) >= 0) { + if (!servos[node_id].state.alive) { + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), + "Starting to read register list of '%d'", node_id); + read_register_list_idx(node_id, 0); + } + servos[node_id].state.alive = true; + } + } + } +} + +void cyphalSystemHardware::write_can() { + // Transmit pending frames from the prioritized TX queues managed by + // libcanard. + const CanardMicrosecond now_usec = getMonotonicMicroseconds(); + struct CanardTxQueue *const que = &canard_tx_queues[0]; + struct CanardTxQueueItem *tqi = + canardTxPeek(que); // Find the highest-priority frame. + while (tqi != NULL) { + // Attempt transmission only if the frame is not yet timed out while waiting + // in the TX queue. Otherwise just drop it and move on to the next one. + if ((tqi->tx_deadline_usec == 0) || (tqi->tx_deadline_usec > now_usec)) { + const struct CanardFrame canard_frame = { + .extended_can_id = tqi->frame.extended_can_id, + .payload = {.size = tqi->frame.payload.size, + .data = tqi->frame.payload.data}}; + // const int16_t result = socketcanPush(sock[ifidx], &canard_frame, 0); // + // Non-blocking write attempt. + const int16_t result = + socketcanPush(can_socket, &canard_frame, + 0); // Non-blocking write attempt. + // digitalWrite(38, 0); /*enable*/delay(1000); + // digitalWrite(38, 1); /*disable*/delay(1000); + + // const int16_t result = 0; + if (result == 0) { + break; // The queue is full, we will try again on the next iteration. + } + if (result < 0) { + return; // SocketCAN interface failure (link down?) + // return -result; // SocketCAN interface failure (link down?) + } + } + + struct CanardTxQueueItem *const mut_tqi = canardTxPop(que, tqi); + canardTxFree(que, &canard, mut_tqi); + + tqi = canardTxPeek(que); + } +} + +void cyphalSystemHardware::read_thread() { + while (true) { + + struct CanardFrame frame; + CanardMicrosecond out_timestamp_usec; + CanardMicrosecond timeout_usec = 0; + bool loopback = false; + + uint8_t payload_buffer[CANARD_MTU_CAN_CLASSIC]; + int ret = socketcanPop(can_socket, &frame, &out_timestamp_usec, + sizeof(payload_buffer), payload_buffer, timeout_usec, + &loopback); + + if (loopback || ret == 0) { + continue; + } + + if (ret < 0) { + RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), + "socketcanPop error (ret=%d)", ret); + return; + } + // RCLCPP_INFO( + // rclcpp::get_logger("cyphalSystemHardware"), + // "ok %d %dms %d: %02X %02X %02X %02X %02X %02X %02X %02X", ret, + // (int)out_timestamp_usec / 1000, (int)frame.payload.size, + // frame.payload.size <= 0 ? 0 : (int)((uint8_t + // *)frame.payload.data)[0], frame.payload.size <= 1 ? 0 : + // (int)((uint8_t *)frame.payload.data)[1], frame.payload.size <= 2 ? 0 + // : (int)((uint8_t *)frame.payload.data)[2], frame.payload.size <= 3 ? + // 0 : (int)((uint8_t *)frame.payload.data)[3], frame.payload.size <= 4 + // ? 0 : (int)((uint8_t *)frame.payload.data)[4], frame.payload.size <= + // 5 ? 0 : (int)((uint8_t *)frame.payload.data)[5], frame.payload.size + // <= 6 ? 0 : (int)((uint8_t *)frame.payload.data)[6], + // frame.payload.size <= 7 ? 0 : (int)((uint8_t + // *)frame.payload.data)[7]); + + // The SocketCAN adapter uses the wall clock for timestamping, but we need + // monotonic. Wall clock can only be used for time synchronization. + const CanardMicrosecond timestamp_usec = getMonotonicMicroseconds(); + struct CanardRxTransfer transfer; + memset(&transfer, 0, sizeof transfer); + const int ifidx = 0; /* interface id */ + const int8_t canard_result = canardRxAccept(&canard, out_timestamp_usec, + &frame, ifidx, &transfer, NULL); + if (canard_result > 0) { + processReceivedTransfer(&transfer, timestamp_usec); + canard.memory.deallocate(canard.memory.user_reference, + transfer.payload.allocated_size, + transfer.payload.data); + } else if (canard_result == -CANARD_ERROR_OUT_OF_MEMORY) { + (void)0; // The frame did not complete a transfer so there is nothing to + // do. + // OOM should never occur if the heap is sized correctly. You can track + // OOM errors via heap API. + RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), "OOM!"); + return; + } else if (canard_result == 0) { + (void)0; // The frame did not complete a transfer so there is nothing to + // do. + using namespace std::chrono_literals; + std::this_thread::sleep_for(10us); + continue; + } else { + assert(false); // No other error can possibly occur at runtime. + // return hardware_interface::return_type::ERROR; + return; + } + + write_can(); + } +} + hardware_interface::CallbackReturn cyphalSystemHardware::on_activate( const rclcpp_lifecycle::State & /*previous_state*/) { // BEGIN: This part here is for exemplary purposes - Please do not copy to // your production code - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "Activating ...please wait..."); + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "Activating"); - /* for (auto i = 0; i < hw_start_sec_; i++) { - rclcpp::sleep_for(std::chrono::seconds(1)); - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "%.1f seconds left...", hw_start_sec_ - i); - } - // END: This part here is for exemplary purposes - Please do not copy to - your - // production code - - // set some default values - for (auto i = 0u; i < hw_positions_.size(); i++) { - if (std::isnan(hw_positions_[i])) { - hw_positions_[i] = 0; - hw_velocities_[i] = 0; - hw_commands_[i] = 0; - } - } - */ RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "Successfully activated!"); + for (auto &[id, s] : servos) { + std::unique_lock lock{s.mtx}; + s.arm_target = ARMED; + } return hardware_interface::CallbackReturn::SUCCESS; } @@ -243,8 +561,7 @@ hardware_interface::CallbackReturn cyphalSystemHardware::on_deactivate( const rclcpp_lifecycle::State & /*previous_state*/) { // BEGIN: This part here is for exemplary purposes - Please do not copy to // your production code - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "Deactivating ...please wait..."); + RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "Deactivating"); /* for (auto i = 0; i < hw_stop_sec_; i++) { rclcpp::sleep_for(std::chrono::seconds(1)); @@ -258,98 +575,32 @@ hardware_interface::CallbackReturn cyphalSystemHardware::on_deactivate( RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), "Successfully deactivated!"); */ + + for (auto &[id, s] : servos) { + + std::unique_lock lock{s.mtx}; + s.arm_target = DISARMED; + } return hardware_interface::CallbackReturn::SUCCESS; } - hardware_interface::return_type cyphalSystemHardware::read(const rclcpp::Time & /*time*/, - const rclcpp::Duration & /*period*/) { + const rclcpp::Duration & /*period*/) { // if (!sync) // return hardware_interface::return_type::ERROR; - // uint8_t read_buf[1024]; - // int read_buf_used = - // read_serial(serial_port_handle, read_buf, sizeof(read_buf)); - // sync->handle_stream((uint8_t *)read_buf, read_buf_used); - // for (auto &[key, value] : interfaces_map) { - // // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // // "Interface %s added (factor: %f).", key.c_str(), - // // value.factor); - // if (!value.command) { - // auto n = sync->get_number(key.c_str()); - // if (n) - // value.value = value.factor * (*n); - // } - // } - - // using namespace std::chrono_literals; - // if (std::chrono::steady_clock::now() - sync->last_pkg_recived > - // std::chrono::milliseconds(1000)) { - // RCLCPP_FATAL(rclcpp::get_logger("cyphalSystemHardware"), - // "last package recivew more than 1000ms ago. aborting!"); - // return hardware_interface::return_type::ERROR; - // } - - // static int counter = 0; - // if (counter++ % 20 == 0) - // for (auto &i : sync->interfaces) { - // if (!i) - // continue; - // auto number_ptr = sync->get_number(i->key.c_str()); - // auto str_ptr = sync->get_string(i->key.c_str()); - // if (number_ptr) - // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // "Sync: %s = %d", i->key.c_str(), *number_ptr); - // if (str_ptr) - // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // "Sync: %s = %s", i->key.c_str(), str_ptr->c_str()); - // } - return hardware_interface::return_type::OK; } hardware_interface::return_type cyphal_hardware_interface ::cyphalSystemHardware::write( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { - // // BEGIN: This part here is for exemplary purposes - Please do not copy to - // // your production code - // if (sync) { - // for (auto &[key, value] : interfaces_map) { - // // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // // "Interface %s added (factor: %f).", key.c_str(), - // // value.factor); - // if (value.command) { - // auto ni = sync->get_or_create_interface(0x01, key.c_str()); - // if (ni) { - - // *(int *)ni->data = (value.value / value.factor); - // ni->send_requested = true; - - // // RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - // // "update: %s set to %d ", key.c_str(), *(int - // // *)ni->data); - // } - // } - // } - // sync->update(); - // } - - /* for (auto i = 0u; i < hw_commands_.size(); i++) { - // Simulate sending commands to the hardware - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "Got command %.5f for '%s'!", hw_commands_[i], - info_.joints[i].name.c_str()); - - hw_velocities_[i] = hw_commands_[i]; - } - RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"), - "Joints successfully written!"); - // END: This part here is for exemplary purposes - Please do not copy to - your - // production code - */ + for (auto &[id, s] : servos) { + std::unique_lock lock{s.mtx}; + send_readyness(s, s.arm_target); + } return hardware_interface::return_type::OK; } diff --git a/hardware/include/cyphal_hardware_interface/cyphal_system.hpp b/hardware/include/cyphal_hardware_interface/cyphal_system.hpp index 6467a4f..68d8db6 100644 --- a/hardware/include/cyphal_hardware_interface/cyphal_system.hpp +++ b/hardware/include/cyphal_hardware_interface/cyphal_system.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include @@ -33,32 +34,80 @@ #include "cyphal_hardware_interface/visibility_control.h" -//#include "cyphal.hpp" +extern "C" { +#include "canard.h" +#include +#include +#include +#include +} + +#include + +#define CAN_REDUNDANCY_FACTOR 1 + +void *canardAllocate(void *const user_reference, const size_t size) { + (void)user_reference; + return malloc(size); +} + +void canardDeallocate(void *const user_reference, const long unsigned int size, + void *const pointer) { + (void)user_reference; + (void)size; + free(pointer); +} namespace cyphal_hardware_interface { +enum arming_state { + DISARMED = 0, + ARMED, +}; +class cyphalUdralServo { +public: + unsigned char node_id = 0xFF; + mutable std::mutex mtx; + std::string cookie = ""; + std::map registers; + struct { + bool alive = false; + bool register_read = false; + std::string requested_register_name; + } state; + + enum arming_state arm_target = DISARMED; + + std::string get_non_read_register_name() const; + bool all_registers_read() const; +}; + class cyphalSystemHardware : public hardware_interface::SystemInterface { public: RCLCPP_SHARED_PTR_DEFINITIONS(cyphalSystemHardware); - constexpr static std::string_view default_serial_port_ = "/dev/ttyACM0"; + constexpr static std::string_view default_if_ = "can0"; + + std::string can_if_; - std::string serial_port_; - bool try_next_port_number; - CYPHAL_HARDWARE_INTERFACE_PUBLIC virtual ~cyphalSystemHardware(); CYPHAL_HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn - on_init(const hardware_interface::HardwareInfo &info) override; + on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) + override; CYPHAL_HARDWARE_INTERFACE_PUBLIC std::vector - export_state_interfaces() override; + export_state_interfaces() override { + return {}; + }; CYPHAL_HARDWARE_INTERFACE_PUBLIC std::vector - export_command_interfaces() override; + export_command_interfaces() override { + return {}; + }; CYPHAL_HARDWARE_INTERFACE_PUBLIC CYPHAL_HARDWARE_INTERFACE_PUBLIC @@ -81,17 +130,42 @@ public: write(const rclcpp::Time &time, const rclcpp::Duration &period) override; private: - struct interface_params { - double value; - double factor; - std::string joint; - bool command; - std::string control_interface; - }; + std::map servos; - int serial_port_handle; + int can_socket = -1; - std::map interfaces_map; + int next_transfer_id = 0; + struct CanardInstance canard; + struct CanardTxQueue canard_tx_queues[CAN_REDUNDANCY_FACTOR]; + + struct CanardMemoryResource canard_memory; + + std::thread read_thread_handle; + + void send(const CanardMicrosecond tx_deadline_usec, + const CanardTransferMetadata *const metadata, + const size_t payload_size, const void *const payload_data, + const CanardMicrosecond now_usec); + + void processReceivedTransfer(const struct CanardRxTransfer *const transfer, + const CanardMicrosecond now_usec); + void read_register_list(int node_id); + void read_register_list_idx(unsigned char node_id, int register_idx); + void read_register(cyphalUdralServo &node_id, std::string name); + void send_readyness(cyphalUdralServo &servo, enum arming_state state); + + void write_can(); + /** + * @brief Reads CAN messages, stops when is_disconnect_requested_ is set to + * true + */ + void read_thread(); + + /** + * @brief Static method to call read_thread via std::thread + * @param context pointer to this + */ + static void read_thread_static(void *context); }; } // namespace cyphal_hardware_interface diff --git a/hardware/include/nunavut/support/serialization.h b/hardware/include/nunavut/support/serialization.h new file mode 100644 index 0000000..c6db938 --- /dev/null +++ b/hardware/include/nunavut/support/serialization.h @@ -0,0 +1,593 @@ +// 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: True +// 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 1 +#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)) + +#ifndef NUNAVUT_ASSERT +// By default Nunavut does not generate assert statements since the logic to halt a program is platform +// dependent and because this header requires an absolute minimum from a platform and from the C standard library. +// Most platforms can simply define "NUNAVUT_ASSERT(x)=assert(x)" ( is always included by Nunavut). +# error "You must either define NUNAVUT_ASSERT or you need to disable assertions" \ + " when generating serialization support code using Nunavut language options" +#endif + +// 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) +{ + NUNAVUT_ASSERT(src != NULL); + NUNAVUT_ASSERT(dst != NULL); + NUNAVUT_ASSERT(src != dst); + 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 + NUNAVUT_ASSERT(length_mod < 8U); + 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; + NUNAVUT_ASSERT(((psrc < pdst) ? ((uintptr_t)(psrc + ((src_offset_bits + length_bits + 8U) / 8U)) <= (uintptr_t)pdst) : 1)); + NUNAVUT_ASSERT(((psrc > pdst) ? ((uintptr_t)(pdst + ((dst_offset_bits + length_bits + 8U) / 8U)) <= (uintptr_t)psrc) : 1)); + 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); + NUNAVUT_ASSERT(size > 0U); + NUNAVUT_ASSERT(size <= 8U); + // 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 + NUNAVUT_ASSERT(mask > 0U); + // 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; + } + NUNAVUT_ASSERT(last_bit == src_off); + } +} + +/// 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) +{ + NUNAVUT_ASSERT(output != NULL); + NUNAVUT_ASSERT(buf != NULL); + 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) +{ + NUNAVUT_ASSERT(buf != NULL); + 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"); + NUNAVUT_ASSERT(buf != NULL); + 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) +{ + NUNAVUT_ASSERT(buf != NULL); + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 8U)); + NUNAVUT_ASSERT(bits <= (sizeof(uint8_t) * 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) +{ + NUNAVUT_ASSERT(buf != NULL); + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 16U)); + NUNAVUT_ASSERT(bits <= (sizeof(uint16_t) * 8U)); + 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) +{ + NUNAVUT_ASSERT(buf != NULL); + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 32U)); + NUNAVUT_ASSERT(bits <= (sizeof(uint32_t) * 8U)); + 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) +{ + NUNAVUT_ASSERT(buf != NULL); + const size_t bits = nunavutSaturateBufferFragmentBitLength(buf_size_bytes, off_bits, nunavutChooseMin(len_bits, 64U)); + NUNAVUT_ASSERT(bits <= (sizeof(uint64_t) * 8U)); + 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/hardware/include/reg/udral/physics/acoustics/Note_0_1.h b/hardware/include/reg/udral/physics/acoustics/Note_0_1.h new file mode 100644 index 0000000..3444104 --- /dev/null +++ b/hardware/include/reg/udral/physics/acoustics/Note_0_1.h @@ -0,0 +1,328 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/acoustics/Note.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.086467 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.acoustics.Note +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_ACOUSTICS_NOTE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_ACOUSTICS_NOTE_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/acoustics/Note.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/acoustics/Note.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/acoustics/Note.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/acoustics/Note.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/acoustics/Note.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 reg_udral_physics_acoustics_Note_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.acoustics.Note.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_acoustics_Note_0_1_FULL_NAME_ "reg.udral.physics.acoustics.Note" +#define reg_udral_physics_acoustics_Note_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.acoustics.Note.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 reg_udral_physics_acoustics_Note_0_1_EXTENT_BYTES_ 12UL +#define reg_udral_physics_acoustics_Note_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(reg_udral_physics_acoustics_Note_0_1_EXTENT_BYTES_ >= reg_udral_physics_acoustics_Note_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.frequency.Scalar.1.0 frequency + uavcan_si_unit_frequency_Scalar_1_0 frequency; + + /// uavcan.si.unit.duration.Scalar.1.0 duration + uavcan_si_unit_duration_Scalar_1_0 duration; + + /// uavcan.si.unit.power.Scalar.1.0 acoustic_power + uavcan_si_unit_power_Scalar_1_0 acoustic_power; +} reg_udral_physics_acoustics_Note_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 reg_udral_physics_acoustics_Note_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 reg_udral_physics_acoustics_Note_0_1_serialize_( + const reg_udral_physics_acoustics_Note_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) < 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; + { // uavcan.si.unit.frequency.Scalar.1.0 frequency + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_frequency_Scalar_1_0_serialize_( + &obj->frequency, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.duration.Scalar.1.0 duration + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_duration_Scalar_1_0_serialize_( + &obj->duration, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.power.Scalar.1.0 acoustic_power + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_power_Scalar_1_0_serialize_( + &obj->acoustic_power, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_acoustics_Note_0_1_deserialize_( + reg_udral_physics_acoustics_Note_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.si.unit.frequency.Scalar.1.0 frequency + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err6_ = uavcan_si_unit_frequency_Scalar_1_0_deserialize_( + &out_obj->frequency, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err6_ < 0) + { + return _err6_; + } + 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.si.unit.duration.Scalar.1.0 duration + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err7_ = uavcan_si_unit_duration_Scalar_1_0_deserialize_( + &out_obj->duration, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err7_ < 0) + { + return _err7_; + } + 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.si.unit.power.Scalar.1.0 acoustic_power + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err8_ = uavcan_si_unit_power_Scalar_1_0_deserialize_( + &out_obj->acoustic_power, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err8_ < 0) + { + return _err8_; + } + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_acoustics_Note_0_1_initialize_(reg_udral_physics_acoustics_Note_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_acoustics_Note_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_ACOUSTICS_NOTE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/dynamics/rotation/PlanarTs_0_1.h b/hardware/include/reg/udral/physics/dynamics/rotation/PlanarTs_0_1.h new file mode 100644 index 0000000..f681fb5 --- /dev/null +++ b/hardware/include/reg/udral/physics/dynamics/rotation/PlanarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/PlanarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.063210 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.dynamics.rotation.PlanarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_DYNAMICS_ROTATION_PLANAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_DYNAMICS_ROTATION_PLANAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/PlanarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/PlanarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/PlanarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/PlanarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/PlanarTs.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 reg_udral_physics_dynamics_rotation_PlanarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.dynamics.rotation.PlanarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_dynamics_rotation_PlanarTs_0_1_FULL_NAME_ "reg.udral.physics.dynamics.rotation.PlanarTs" +#define reg_udral_physics_dynamics_rotation_PlanarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.dynamics.rotation.PlanarTs.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 reg_udral_physics_dynamics_rotation_PlanarTs_0_1_EXTENT_BYTES_ 23UL +#define reg_udral_physics_dynamics_rotation_PlanarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 23UL +static_assert(reg_udral_physics_dynamics_rotation_PlanarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_dynamics_rotation_PlanarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.dynamics.rotation.Planar.0.1 value + reg_udral_physics_dynamics_rotation_Planar_0_1 value; +} reg_udral_physics_dynamics_rotation_PlanarTs_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 reg_udral_physics_dynamics_rotation_PlanarTs_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 reg_udral_physics_dynamics_rotation_PlanarTs_0_1_serialize_( + const reg_udral_physics_dynamics_rotation_PlanarTs_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.dynamics.rotation.Planar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 16UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_dynamics_rotation_Planar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 128ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 184ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_dynamics_rotation_PlanarTs_0_1_deserialize_( + reg_udral_physics_dynamics_rotation_PlanarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.dynamics.rotation.Planar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_dynamics_rotation_Planar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_dynamics_rotation_PlanarTs_0_1_initialize_(reg_udral_physics_dynamics_rotation_PlanarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_dynamics_rotation_PlanarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_DYNAMICS_ROTATION_PLANAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/dynamics/rotation/Planar_0_1.h b/hardware/include/reg/udral/physics/dynamics/rotation/Planar_0_1.h new file mode 100644 index 0000000..b172a39 --- /dev/null +++ b/hardware/include/reg/udral/physics/dynamics/rotation/Planar_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/Planar.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.060070 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.dynamics.rotation.Planar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_DYNAMICS_ROTATION_PLANAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_DYNAMICS_ROTATION_PLANAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/Planar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/Planar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/Planar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/Planar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/rotation/Planar.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 reg_udral_physics_dynamics_rotation_Planar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.dynamics.rotation.Planar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_dynamics_rotation_Planar_0_1_FULL_NAME_ "reg.udral.physics.dynamics.rotation.Planar" +#define reg_udral_physics_dynamics_rotation_Planar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.dynamics.rotation.Planar.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 reg_udral_physics_dynamics_rotation_Planar_0_1_EXTENT_BYTES_ 16UL +#define reg_udral_physics_dynamics_rotation_Planar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 16UL +static_assert(reg_udral_physics_dynamics_rotation_Planar_0_1_EXTENT_BYTES_ >= reg_udral_physics_dynamics_rotation_Planar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.rotation.Planar.0.1 kinematics + reg_udral_physics_kinematics_rotation_Planar_0_1 kinematics; + + /// uavcan.si.unit.torque.Scalar.1.0 torque + uavcan_si_unit_torque_Scalar_1_0 _torque; +} reg_udral_physics_dynamics_rotation_Planar_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 reg_udral_physics_dynamics_rotation_Planar_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 reg_udral_physics_dynamics_rotation_Planar_0_1_serialize_( + const reg_udral_physics_dynamics_rotation_Planar_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) < 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; + { // reg.udral.physics.kinematics.rotation.Planar.0.1 kinematics + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_rotation_Planar_0_1_serialize_( + &obj->kinematics, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 96ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.torque.Scalar.1.0 torque + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_torque_Scalar_1_0_serialize_( + &obj->_torque, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 128ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_dynamics_rotation_Planar_0_1_deserialize_( + reg_udral_physics_dynamics_rotation_Planar_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; + // reg.udral.physics.kinematics.rotation.Planar.0.1 kinematics + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_rotation_Planar_0_1_deserialize_( + &out_obj->kinematics, &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.si.unit.torque.Scalar.1.0 torque + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_torque_Scalar_1_0_deserialize_( + &out_obj->_torque, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_dynamics_rotation_Planar_0_1_initialize_(reg_udral_physics_dynamics_rotation_Planar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_dynamics_rotation_Planar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_DYNAMICS_ROTATION_PLANAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/dynamics/translation/LinearTs_0_1.h b/hardware/include/reg/udral/physics/dynamics/translation/LinearTs_0_1.h new file mode 100644 index 0000000..d4dfff8 --- /dev/null +++ b/hardware/include/reg/udral/physics/dynamics/translation/LinearTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/LinearTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.069432 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.dynamics.translation.LinearTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_DYNAMICS_TRANSLATION_LINEAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_DYNAMICS_TRANSLATION_LINEAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/LinearTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/LinearTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/LinearTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/LinearTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/LinearTs.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 reg_udral_physics_dynamics_translation_LinearTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.dynamics.translation.LinearTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_dynamics_translation_LinearTs_0_1_FULL_NAME_ "reg.udral.physics.dynamics.translation.LinearTs" +#define reg_udral_physics_dynamics_translation_LinearTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.dynamics.translation.LinearTs.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 reg_udral_physics_dynamics_translation_LinearTs_0_1_EXTENT_BYTES_ 23UL +#define reg_udral_physics_dynamics_translation_LinearTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 23UL +static_assert(reg_udral_physics_dynamics_translation_LinearTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_dynamics_translation_LinearTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.dynamics.translation.Linear.0.1 value + reg_udral_physics_dynamics_translation_Linear_0_1 value; +} reg_udral_physics_dynamics_translation_LinearTs_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 reg_udral_physics_dynamics_translation_LinearTs_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 reg_udral_physics_dynamics_translation_LinearTs_0_1_serialize_( + const reg_udral_physics_dynamics_translation_LinearTs_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.dynamics.translation.Linear.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 16UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_dynamics_translation_Linear_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 128ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 184ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_dynamics_translation_LinearTs_0_1_deserialize_( + reg_udral_physics_dynamics_translation_LinearTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.dynamics.translation.Linear.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_dynamics_translation_Linear_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_dynamics_translation_LinearTs_0_1_initialize_(reg_udral_physics_dynamics_translation_LinearTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_dynamics_translation_LinearTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_DYNAMICS_TRANSLATION_LINEAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/dynamics/translation/Linear_0_1.h b/hardware/include/reg/udral/physics/dynamics/translation/Linear_0_1.h new file mode 100644 index 0000000..4f2917f --- /dev/null +++ b/hardware/include/reg/udral/physics/dynamics/translation/Linear_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/Linear.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.066286 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.dynamics.translation.Linear +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_DYNAMICS_TRANSLATION_LINEAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_DYNAMICS_TRANSLATION_LINEAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/Linear.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/Linear.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/Linear.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/Linear.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/dynamics/translation/Linear.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 reg_udral_physics_dynamics_translation_Linear_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.dynamics.translation.Linear.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_dynamics_translation_Linear_0_1_FULL_NAME_ "reg.udral.physics.dynamics.translation.Linear" +#define reg_udral_physics_dynamics_translation_Linear_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.dynamics.translation.Linear.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 reg_udral_physics_dynamics_translation_Linear_0_1_EXTENT_BYTES_ 16UL +#define reg_udral_physics_dynamics_translation_Linear_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 16UL +static_assert(reg_udral_physics_dynamics_translation_Linear_0_1_EXTENT_BYTES_ >= reg_udral_physics_dynamics_translation_Linear_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.translation.Linear.0.1 kinematics + reg_udral_physics_kinematics_translation_Linear_0_1 kinematics; + + /// uavcan.si.unit.force.Scalar.1.0 force + uavcan_si_unit_force_Scalar_1_0 force; +} reg_udral_physics_dynamics_translation_Linear_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 reg_udral_physics_dynamics_translation_Linear_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 reg_udral_physics_dynamics_translation_Linear_0_1_serialize_( + const reg_udral_physics_dynamics_translation_Linear_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) < 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; + { // reg.udral.physics.kinematics.translation.Linear.0.1 kinematics + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_translation_Linear_0_1_serialize_( + &obj->kinematics, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 96ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.force.Scalar.1.0 force + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_force_Scalar_1_0_serialize_( + &obj->force, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 128ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_dynamics_translation_Linear_0_1_deserialize_( + reg_udral_physics_dynamics_translation_Linear_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; + // reg.udral.physics.kinematics.translation.Linear.0.1 kinematics + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_translation_Linear_0_1_deserialize_( + &out_obj->kinematics, &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.si.unit.force.Scalar.1.0 force + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_force_Scalar_1_0_deserialize_( + &out_obj->force, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_dynamics_translation_Linear_0_1_initialize_(reg_udral_physics_dynamics_translation_Linear_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_dynamics_translation_Linear_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_DYNAMICS_TRANSLATION_LINEAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/electricity/PowerTs_0_1.h b/hardware/include/reg/udral/physics/electricity/PowerTs_0_1.h new file mode 100644 index 0000000..df09428 --- /dev/null +++ b/hardware/include/reg/udral/physics/electricity/PowerTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/PowerTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.050472 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.electricity.PowerTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_ELECTRICITY_POWER_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_ELECTRICITY_POWER_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/PowerTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/PowerTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/PowerTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/PowerTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/PowerTs.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 reg_udral_physics_electricity_PowerTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.electricity.PowerTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_electricity_PowerTs_0_1_FULL_NAME_ "reg.udral.physics.electricity.PowerTs" +#define reg_udral_physics_electricity_PowerTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.electricity.PowerTs.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 reg_udral_physics_electricity_PowerTs_0_1_EXTENT_BYTES_ 15UL +#define reg_udral_physics_electricity_PowerTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 15UL +static_assert(reg_udral_physics_electricity_PowerTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_electricity_PowerTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.electricity.Power.0.1 value + reg_udral_physics_electricity_Power_0_1 value; +} reg_udral_physics_electricity_PowerTs_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 reg_udral_physics_electricity_PowerTs_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 reg_udral_physics_electricity_PowerTs_0_1_serialize_( + const reg_udral_physics_electricity_PowerTs_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; + { // uavcan.time.SynchronizedTimestamp.1.0 timestamp + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.electricity.Power.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 8UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_electricity_Power_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 64ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 120ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_electricity_PowerTs_0_1_deserialize_( + reg_udral_physics_electricity_PowerTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.electricity.Power.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_electricity_Power_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_electricity_PowerTs_0_1_initialize_(reg_udral_physics_electricity_PowerTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_electricity_PowerTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_ELECTRICITY_POWER_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/electricity/Power_0_1.h b/hardware/include/reg/udral/physics/electricity/Power_0_1.h new file mode 100644 index 0000000..3bb04d2 --- /dev/null +++ b/hardware/include/reg/udral/physics/electricity/Power_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Power.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.047408 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.electricity.Power +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_ELECTRICITY_POWER_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_ELECTRICITY_POWER_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Power.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Power.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Power.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Power.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Power.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 reg_udral_physics_electricity_Power_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.electricity.Power.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_electricity_Power_0_1_FULL_NAME_ "reg.udral.physics.electricity.Power" +#define reg_udral_physics_electricity_Power_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.electricity.Power.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 reg_udral_physics_electricity_Power_0_1_EXTENT_BYTES_ 8UL +#define reg_udral_physics_electricity_Power_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(reg_udral_physics_electricity_Power_0_1_EXTENT_BYTES_ >= reg_udral_physics_electricity_Power_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.electric_current.Scalar.1.0 current + uavcan_si_unit_electric_current_Scalar_1_0 current; + + /// uavcan.si.unit.voltage.Scalar.1.0 voltage + uavcan_si_unit_voltage_Scalar_1_0 voltage; +} reg_udral_physics_electricity_Power_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 reg_udral_physics_electricity_Power_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 reg_udral_physics_electricity_Power_0_1_serialize_( + const reg_udral_physics_electricity_Power_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) < 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; + { // uavcan.si.unit.electric_current.Scalar.1.0 current + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + &obj->current, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.voltage.Scalar.1.0 voltage + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_voltage_Scalar_1_0_serialize_( + &obj->voltage, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_electricity_Power_0_1_deserialize_( + reg_udral_physics_electricity_Power_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.si.unit.electric_current.Scalar.1.0 current + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + &out_obj->current, &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.si.unit.voltage.Scalar.1.0 voltage + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_voltage_Scalar_1_0_deserialize_( + &out_obj->voltage, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_electricity_Power_0_1_initialize_(reg_udral_physics_electricity_Power_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_electricity_Power_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_ELECTRICITY_POWER_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/electricity/SourceTs_0_1.h b/hardware/include/reg/udral/physics/electricity/SourceTs_0_1.h new file mode 100644 index 0000000..538e5db --- /dev/null +++ b/hardware/include/reg/udral/physics/electricity/SourceTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/SourceTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.057032 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.electricity.SourceTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_ELECTRICITY_SOURCE_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_ELECTRICITY_SOURCE_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/SourceTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/SourceTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/SourceTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/SourceTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/SourceTs.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 reg_udral_physics_electricity_SourceTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.electricity.SourceTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_electricity_SourceTs_0_1_FULL_NAME_ "reg.udral.physics.electricity.SourceTs" +#define reg_udral_physics_electricity_SourceTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.electricity.SourceTs.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 reg_udral_physics_electricity_SourceTs_0_1_EXTENT_BYTES_ 23UL +#define reg_udral_physics_electricity_SourceTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 23UL +static_assert(reg_udral_physics_electricity_SourceTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_electricity_SourceTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.electricity.Source.0.1 value + reg_udral_physics_electricity_Source_0_1 value; +} reg_udral_physics_electricity_SourceTs_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 reg_udral_physics_electricity_SourceTs_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 reg_udral_physics_electricity_SourceTs_0_1_serialize_( + const reg_udral_physics_electricity_SourceTs_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.electricity.Source.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 16UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_electricity_Source_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 128ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 184ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_electricity_SourceTs_0_1_deserialize_( + reg_udral_physics_electricity_SourceTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.electricity.Source.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_electricity_Source_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_electricity_SourceTs_0_1_initialize_(reg_udral_physics_electricity_SourceTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_electricity_SourceTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_ELECTRICITY_SOURCE_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/electricity/Source_0_1.h b/hardware/include/reg/udral/physics/electricity/Source_0_1.h new file mode 100644 index 0000000..dec3c2c --- /dev/null +++ b/hardware/include/reg/udral/physics/electricity/Source_0_1.h @@ -0,0 +1,327 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Source.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.053444 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.electricity.Source +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_ELECTRICITY_SOURCE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_ELECTRICITY_SOURCE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Source.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Source.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Source.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Source.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/electricity/Source.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 reg_udral_physics_electricity_Source_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.electricity.Source.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_electricity_Source_0_1_FULL_NAME_ "reg.udral.physics.electricity.Source" +#define reg_udral_physics_electricity_Source_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.electricity.Source.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 reg_udral_physics_electricity_Source_0_1_EXTENT_BYTES_ 16UL +#define reg_udral_physics_electricity_Source_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 16UL +static_assert(reg_udral_physics_electricity_Source_0_1_EXTENT_BYTES_ >= reg_udral_physics_electricity_Source_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.electricity.Power.0.1 power + reg_udral_physics_electricity_Power_0_1 power; + + /// uavcan.si.unit.energy.Scalar.1.0 energy + uavcan_si_unit_energy_Scalar_1_0 energy; + + /// uavcan.si.unit.energy.Scalar.1.0 full_energy + uavcan_si_unit_energy_Scalar_1_0 full_energy; +} reg_udral_physics_electricity_Source_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 reg_udral_physics_electricity_Source_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 reg_udral_physics_electricity_Source_0_1_serialize_( + const reg_udral_physics_electricity_Source_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) < 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; + { // reg.udral.physics.electricity.Power.0.1 power + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 8UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_electricity_Power_0_1_serialize_( + &obj->power, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 64ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.energy.Scalar.1.0 energy + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_energy_Scalar_1_0_serialize_( + &obj->energy, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.energy.Scalar.1.0 full_energy + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_energy_Scalar_1_0_serialize_( + &obj->full_energy, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 128ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_electricity_Source_0_1_deserialize_( + reg_udral_physics_electricity_Source_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; + // reg.udral.physics.electricity.Power.0.1 power + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err6_ = reg_udral_physics_electricity_Power_0_1_deserialize_( + &out_obj->power, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err6_ < 0) + { + return _err6_; + } + 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.si.unit.energy.Scalar.1.0 energy + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err7_ = uavcan_si_unit_energy_Scalar_1_0_deserialize_( + &out_obj->energy, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err7_ < 0) + { + return _err7_; + } + 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.si.unit.energy.Scalar.1.0 full_energy + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err8_ = uavcan_si_unit_energy_Scalar_1_0_deserialize_( + &out_obj->full_energy, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err8_ < 0) + { + return _err8_; + } + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_electricity_Source_0_1_initialize_(reg_udral_physics_electricity_Source_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_electricity_Source_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_ELECTRICITY_SOURCE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/PointStateVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/PointStateVarTs_0_1.h new file mode 100644 index 0000000..08fd0b4 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/PointStateVarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.012177 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.PointStateVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVarTs.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 reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.PointStateVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.PointStateVarTs" +#define reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.PointStateVarTs.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 reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_EXTENT_BYTES_ 67UL +#define reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 67UL +static_assert(reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.cartesian.PointStateVar.0.1 value + reg_udral_physics_kinematics_cartesian_PointStateVar_0_1 value; +} reg_udral_physics_kinematics_cartesian_PointStateVarTs_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 reg_udral_physics_kinematics_cartesian_PointStateVarTs_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 reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_PointStateVarTs_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) < 536UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.PointStateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 480ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 60UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 480ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 536ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_PointStateVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.cartesian.PointStateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_initialize_(reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_PointStateVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/PointStateVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/PointStateVar_0_1.h new file mode 100644 index 0000000..7c921ad --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/PointStateVar_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.009067 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.PointStateVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointStateVar.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 reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.PointStateVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.PointStateVar" +#define reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.PointStateVar.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 reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_EXTENT_BYTES_ 60UL +#define reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 60UL +static_assert(reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.PointVar.0.1 position + reg_udral_physics_kinematics_cartesian_PointVar_0_1 position; + + /// reg.udral.physics.kinematics.translation.Velocity3Var.0.2 velocity + reg_udral_physics_kinematics_translation_Velocity3Var_0_2 velocity; +} reg_udral_physics_kinematics_cartesian_PointStateVar_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 reg_udral_physics_kinematics_cartesian_PointStateVar_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 reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_PointStateVar_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) < 480UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.PointVar.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 288ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 36UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_PointVar_0_1_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 288ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.translation.Velocity3Var.0.2 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_translation_Velocity3Var_0_2_serialize_( + &obj->velocity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 192ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 480ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_PointStateVar_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; + // reg.udral.physics.kinematics.cartesian.PointVar.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_cartesian_PointVar_0_1_deserialize_( + &out_obj->position, &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. + // reg.udral.physics.kinematics.translation.Velocity3Var.0.2 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_translation_Velocity3Var_0_2_deserialize_( + &out_obj->velocity, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_initialize_(reg_udral_physics_kinematics_cartesian_PointStateVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_PointStateVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/PointState_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/PointState_0_1.h new file mode 100644 index 0000000..dd17602 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/PointState_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointState.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.005993 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.PointState +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointState.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointState.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointState.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointState.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointState.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 reg_udral_physics_kinematics_cartesian_PointState_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.PointState.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_PointState_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.PointState" +#define reg_udral_physics_kinematics_cartesian_PointState_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.PointState.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 reg_udral_physics_kinematics_cartesian_PointState_0_1_EXTENT_BYTES_ 36UL +#define reg_udral_physics_kinematics_cartesian_PointState_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 36UL +static_assert(reg_udral_physics_kinematics_cartesian_PointState_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_PointState_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.Point.0.1 position + reg_udral_physics_kinematics_cartesian_Point_0_1 position; + + /// uavcan.si.unit.velocity.Vector3.1.0 velocity + uavcan_si_unit_velocity_Vector3_1_0 velocity; +} reg_udral_physics_kinematics_cartesian_PointState_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 reg_udral_physics_kinematics_cartesian_PointState_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 reg_udral_physics_kinematics_cartesian_PointState_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_PointState_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) < 288UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_Point_0_1_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.velocity.Vector3.1.0 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_velocity_Vector3_1_0_serialize_( + &obj->velocity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 96ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 288ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_PointState_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_PointState_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; + // reg.udral.physics.kinematics.cartesian.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_cartesian_Point_0_1_deserialize_( + &out_obj->position, &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.si.unit.velocity.Vector3.1.0 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_velocity_Vector3_1_0_deserialize_( + &out_obj->velocity, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_PointState_0_1_initialize_(reg_udral_physics_kinematics_cartesian_PointState_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_PointState_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_STATE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/PointVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/PointVar_0_1.h new file mode 100644 index 0000000..958ef25 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/PointVar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.015324 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.PointVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PointVar.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 reg_udral_physics_kinematics_cartesian_PointVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.PointVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_PointVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.PointVar" +#define reg_udral_physics_kinematics_cartesian_PointVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.PointVar.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 reg_udral_physics_kinematics_cartesian_PointVar_0_1_EXTENT_BYTES_ 36UL +#define reg_udral_physics_kinematics_cartesian_PointVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 36UL +static_assert(reg_udral_physics_kinematics_cartesian_PointVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_PointVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[6] covariance_urt +#define reg_udral_physics_kinematics_cartesian_PointVar_0_1_covariance_urt_ARRAY_CAPACITY_ 6U +#define reg_udral_physics_kinematics_cartesian_PointVar_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.Point.0.1 value + reg_udral_physics_kinematics_cartesian_Point_0_1 value; + + /// saturated float16[6] covariance_urt + float covariance_urt[6]; +} reg_udral_physics_kinematics_cartesian_PointVar_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 reg_udral_physics_kinematics_cartesian_PointVar_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 reg_udral_physics_kinematics_cartesian_PointVar_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_PointVar_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) < 288UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.Point.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_Point_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 288ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_PointVar_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_PointVar_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; + // reg.udral.physics.kinematics.cartesian.Point.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = reg_udral_physics_kinematics_cartesian_Point_0_1_deserialize_( + &out_obj->value, &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 float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_PointVar_0_1_initialize_(reg_udral_physics_kinematics_cartesian_PointVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_PointVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/Point_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/Point_0_1.h new file mode 100644 index 0000000..1456093 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/Point_0_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Point.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.003348 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.Point +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Point.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Point.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Point.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Point.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Point.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 reg_udral_physics_kinematics_cartesian_Point_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.Point.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_Point_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.Point" +#define reg_udral_physics_kinematics_cartesian_Point_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.Point.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 reg_udral_physics_kinematics_cartesian_Point_0_1_EXTENT_BYTES_ 24UL +#define reg_udral_physics_kinematics_cartesian_Point_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 24UL +static_assert(reg_udral_physics_kinematics_cartesian_Point_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_Point_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.length.WideVector3.1.0 value + uavcan_si_unit_length_WideVector3_1_0 value; +} reg_udral_physics_kinematics_cartesian_Point_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 reg_udral_physics_kinematics_cartesian_Point_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 reg_udral_physics_kinematics_cartesian_Point_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_Point_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) < 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; + { // uavcan.si.unit.length.WideVector3.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_length_WideVector3_1_0_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 192ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_Point_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_Point_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.si.unit.length.WideVector3.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err2_ = uavcan_si_unit_length_WideVector3_1_0_deserialize_( + &out_obj->value, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_Point_0_1_initialize_(reg_udral_physics_kinematics_cartesian_Point_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_Point_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POINT_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/PoseVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/PoseVarTs_0_1.h new file mode 100644 index 0000000..0983d48 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/PoseVarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.024772 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.PoseVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVarTs.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 reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.PoseVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.PoseVarTs" +#define reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.PoseVarTs.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 reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_EXTENT_BYTES_ 89UL +#define reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 89UL +static_assert(reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.cartesian.PoseVar.0.1 value + reg_udral_physics_kinematics_cartesian_PoseVar_0_1 value; +} reg_udral_physics_kinematics_cartesian_PoseVarTs_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 reg_udral_physics_kinematics_cartesian_PoseVarTs_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 reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_PoseVarTs_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) < 712UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.PoseVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 656ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 82UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_PoseVar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 656ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 712ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_PoseVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.cartesian.PoseVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_PoseVar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_initialize_(reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_PoseVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/PoseVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/PoseVar_0_1.h new file mode 100644 index 0000000..228b827 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/PoseVar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.021585 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.PoseVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/PoseVar.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 reg_udral_physics_kinematics_cartesian_PoseVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.PoseVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_PoseVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.PoseVar" +#define reg_udral_physics_kinematics_cartesian_PoseVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.PoseVar.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 reg_udral_physics_kinematics_cartesian_PoseVar_0_1_EXTENT_BYTES_ 82UL +#define reg_udral_physics_kinematics_cartesian_PoseVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 82UL +static_assert(reg_udral_physics_kinematics_cartesian_PoseVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_PoseVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[21] covariance_urt +#define reg_udral_physics_kinematics_cartesian_PoseVar_0_1_covariance_urt_ARRAY_CAPACITY_ 21U +#define reg_udral_physics_kinematics_cartesian_PoseVar_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.Pose.0.1 value + reg_udral_physics_kinematics_cartesian_Pose_0_1 value; + + /// saturated float16[21] covariance_urt + float covariance_urt[21]; +} reg_udral_physics_kinematics_cartesian_PoseVar_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 reg_udral_physics_kinematics_cartesian_PoseVar_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 reg_udral_physics_kinematics_cartesian_PoseVar_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_PoseVar_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) < 656UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.Pose.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 320ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 40UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_Pose_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 320ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[21] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 336ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 21UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 336ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 656ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_PoseVar_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_PoseVar_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; + // reg.udral.physics.kinematics.cartesian.Pose.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = reg_udral_physics_kinematics_cartesian_Pose_0_1_deserialize_( + &out_obj->value, &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 float16[21] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 21UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_PoseVar_0_1_initialize_(reg_udral_physics_kinematics_cartesian_PoseVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_PoseVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/Pose_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/Pose_0_1.h new file mode 100644 index 0000000..3d4e4d8 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/Pose_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Pose.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.018573 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.Pose +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Pose.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Pose.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Pose.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Pose.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Pose.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 reg_udral_physics_kinematics_cartesian_Pose_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.Pose.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_Pose_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.Pose" +#define reg_udral_physics_kinematics_cartesian_Pose_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.Pose.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 reg_udral_physics_kinematics_cartesian_Pose_0_1_EXTENT_BYTES_ 40UL +#define reg_udral_physics_kinematics_cartesian_Pose_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 40UL +static_assert(reg_udral_physics_kinematics_cartesian_Pose_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_Pose_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.Point.0.1 position + reg_udral_physics_kinematics_cartesian_Point_0_1 position; + + /// uavcan.si.unit.angle.Quaternion.1.0 orientation + uavcan_si_unit_angle_Quaternion_1_0 orientation; +} reg_udral_physics_kinematics_cartesian_Pose_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 reg_udral_physics_kinematics_cartesian_Pose_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 reg_udral_physics_kinematics_cartesian_Pose_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_Pose_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) < 320UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_Point_0_1_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.angle.Quaternion.1.0 orientation + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 16UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_angle_Quaternion_1_0_serialize_( + &obj->orientation, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 128ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 320ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_Pose_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_Pose_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; + // reg.udral.physics.kinematics.cartesian.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_cartesian_Point_0_1_deserialize_( + &out_obj->position, &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.si.unit.angle.Quaternion.1.0 orientation + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_angle_Quaternion_1_0_deserialize_( + &out_obj->orientation, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_Pose_0_1_initialize_(reg_udral_physics_kinematics_cartesian_Pose_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_Pose_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_POSE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/StateVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/StateVarTs_0_1.h new file mode 100644 index 0000000..ff85fed --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/StateVarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.034263 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.StateVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVarTs.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 reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.StateVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.StateVarTs" +#define reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.StateVarTs.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 reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_EXTENT_BYTES_ 155UL +#define reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 155UL +static_assert(reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.cartesian.StateVar.0.1 value + reg_udral_physics_kinematics_cartesian_StateVar_0_1 value; +} reg_udral_physics_kinematics_cartesian_StateVarTs_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 reg_udral_physics_kinematics_cartesian_StateVarTs_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 reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_StateVarTs_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) < 1240UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.StateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1184ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 148UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_StateVar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 1184ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 1240ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_StateVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.cartesian.StateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_StateVar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_initialize_(reg_udral_physics_kinematics_cartesian_StateVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_StateVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/StateVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/StateVar_0_1.h new file mode 100644 index 0000000..de3d136 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/StateVar_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.030921 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.StateVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/StateVar.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 reg_udral_physics_kinematics_cartesian_StateVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.StateVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_StateVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.StateVar" +#define reg_udral_physics_kinematics_cartesian_StateVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.StateVar.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 reg_udral_physics_kinematics_cartesian_StateVar_0_1_EXTENT_BYTES_ 148UL +#define reg_udral_physics_kinematics_cartesian_StateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 148UL +static_assert(reg_udral_physics_kinematics_cartesian_StateVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_StateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.PoseVar.0.1 pose + reg_udral_physics_kinematics_cartesian_PoseVar_0_1 pose; + + /// reg.udral.physics.kinematics.cartesian.TwistVar.0.1 twist + reg_udral_physics_kinematics_cartesian_TwistVar_0_1 twist; +} reg_udral_physics_kinematics_cartesian_StateVar_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 reg_udral_physics_kinematics_cartesian_StateVar_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 reg_udral_physics_kinematics_cartesian_StateVar_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_StateVar_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) < 1184UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.PoseVar.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 656ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 82UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_PoseVar_0_1_serialize_( + &obj->pose, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 656ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.TwistVar.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 528ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 66UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_serialize_( + &obj->twist, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 528ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 1184ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_StateVar_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_StateVar_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; + // reg.udral.physics.kinematics.cartesian.PoseVar.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_cartesian_PoseVar_0_1_deserialize_( + &out_obj->pose, &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. + // reg.udral.physics.kinematics.cartesian.TwistVar.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_deserialize_( + &out_obj->twist, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_StateVar_0_1_initialize_(reg_udral_physics_kinematics_cartesian_StateVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_StateVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/State_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/State_0_1.h new file mode 100644 index 0000000..1c82cfa --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/State_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/State.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.027864 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.State +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/State.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/State.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/State.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/State.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/State.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 reg_udral_physics_kinematics_cartesian_State_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.State.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_State_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.State" +#define reg_udral_physics_kinematics_cartesian_State_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.State.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 reg_udral_physics_kinematics_cartesian_State_0_1_EXTENT_BYTES_ 64UL +#define reg_udral_physics_kinematics_cartesian_State_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 64UL +static_assert(reg_udral_physics_kinematics_cartesian_State_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_State_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.Pose.0.1 pose + reg_udral_physics_kinematics_cartesian_Pose_0_1 pose; + + /// reg.udral.physics.kinematics.cartesian.Twist.0.1 twist + reg_udral_physics_kinematics_cartesian_Twist_0_1 twist; +} reg_udral_physics_kinematics_cartesian_State_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 reg_udral_physics_kinematics_cartesian_State_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 reg_udral_physics_kinematics_cartesian_State_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_State_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; + { // reg.udral.physics.kinematics.cartesian.Pose.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 320ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 40UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_Pose_0_1_serialize_( + &obj->pose, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 320ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.Twist.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_Twist_0_1_serialize_( + &obj->twist, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 192ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 512ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_State_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_State_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; + // reg.udral.physics.kinematics.cartesian.Pose.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_cartesian_Pose_0_1_deserialize_( + &out_obj->pose, &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. + // reg.udral.physics.kinematics.cartesian.Twist.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_Twist_0_1_deserialize_( + &out_obj->twist, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_State_0_1_initialize_(reg_udral_physics_kinematics_cartesian_State_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_State_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_STATE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/TwistVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/TwistVarTs_0_1.h new file mode 100644 index 0000000..99a04c7 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/TwistVarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.044347 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.TwistVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVarTs.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 reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.TwistVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.TwistVarTs" +#define reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.TwistVarTs.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 reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_EXTENT_BYTES_ 73UL +#define reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 73UL +static_assert(reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.cartesian.TwistVar.0.1 value + reg_udral_physics_kinematics_cartesian_TwistVar_0_1 value; +} reg_udral_physics_kinematics_cartesian_TwistVarTs_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 reg_udral_physics_kinematics_cartesian_TwistVarTs_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 reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_TwistVarTs_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) < 584UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.TwistVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 528ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 66UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 528ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 584ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_TwistVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.cartesian.TwistVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_initialize_(reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_TwistVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/TwistVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/TwistVar_0_1.h new file mode 100644 index 0000000..a08d908 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/TwistVar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.041120 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.TwistVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/TwistVar.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 reg_udral_physics_kinematics_cartesian_TwistVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.TwistVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_TwistVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.TwistVar" +#define reg_udral_physics_kinematics_cartesian_TwistVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.TwistVar.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 reg_udral_physics_kinematics_cartesian_TwistVar_0_1_EXTENT_BYTES_ 66UL +#define reg_udral_physics_kinematics_cartesian_TwistVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 66UL +static_assert(reg_udral_physics_kinematics_cartesian_TwistVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_TwistVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[21] covariance_urt +#define reg_udral_physics_kinematics_cartesian_TwistVar_0_1_covariance_urt_ARRAY_CAPACITY_ 21U +#define reg_udral_physics_kinematics_cartesian_TwistVar_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// reg.udral.physics.kinematics.cartesian.Twist.0.1 value + reg_udral_physics_kinematics_cartesian_Twist_0_1 value; + + /// saturated float16[21] covariance_urt + float covariance_urt[21]; +} reg_udral_physics_kinematics_cartesian_TwistVar_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 reg_udral_physics_kinematics_cartesian_TwistVar_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 reg_udral_physics_kinematics_cartesian_TwistVar_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_TwistVar_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) < 528UL) + { + 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; + { // reg.udral.physics.kinematics.cartesian.Twist.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_cartesian_Twist_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[21] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 336ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 21UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 336ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 528ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_TwistVar_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_TwistVar_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; + // reg.udral.physics.kinematics.cartesian.Twist.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = reg_udral_physics_kinematics_cartesian_Twist_0_1_deserialize_( + &out_obj->value, &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 float16[21] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 21UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_TwistVar_0_1_initialize_(reg_udral_physics_kinematics_cartesian_TwistVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/cartesian/Twist_0_1.h b/hardware/include/reg/udral/physics/kinematics/cartesian/Twist_0_1.h new file mode 100644 index 0000000..d0dd5ce --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/cartesian/Twist_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Twist.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.037804 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.cartesian.Twist +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Twist.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Twist.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Twist.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Twist.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/cartesian/Twist.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 reg_udral_physics_kinematics_cartesian_Twist_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.cartesian.Twist.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_cartesian_Twist_0_1_FULL_NAME_ "reg.udral.physics.kinematics.cartesian.Twist" +#define reg_udral_physics_kinematics_cartesian_Twist_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.cartesian.Twist.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 reg_udral_physics_kinematics_cartesian_Twist_0_1_EXTENT_BYTES_ 24UL +#define reg_udral_physics_kinematics_cartesian_Twist_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 24UL +static_assert(reg_udral_physics_kinematics_cartesian_Twist_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_cartesian_Twist_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.velocity.Vector3.1.0 linear + uavcan_si_unit_velocity_Vector3_1_0 linear; + + /// uavcan.si.unit.angular_velocity.Vector3.1.0 angular + uavcan_si_unit_angular_velocity_Vector3_1_0 angular; +} reg_udral_physics_kinematics_cartesian_Twist_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 reg_udral_physics_kinematics_cartesian_Twist_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 reg_udral_physics_kinematics_cartesian_Twist_0_1_serialize_( + const reg_udral_physics_kinematics_cartesian_Twist_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) < 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; + { // uavcan.si.unit.velocity.Vector3.1.0 linear + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_velocity_Vector3_1_0_serialize_( + &obj->linear, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 96ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.angular_velocity.Vector3.1.0 angular + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_angular_velocity_Vector3_1_0_serialize_( + &obj->angular, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 96ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 192ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_cartesian_Twist_0_1_deserialize_( + reg_udral_physics_kinematics_cartesian_Twist_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.si.unit.velocity.Vector3.1.0 linear + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = uavcan_si_unit_velocity_Vector3_1_0_deserialize_( + &out_obj->linear, &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.si.unit.angular_velocity.Vector3.1.0 angular + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_angular_velocity_Vector3_1_0_deserialize_( + &out_obj->angular, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_cartesian_Twist_0_1_initialize_(reg_udral_physics_kinematics_cartesian_Twist_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_cartesian_Twist_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_CARTESIAN_TWIST_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/PointStateVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/PointStateVarTs_0_1.h new file mode 100644 index 0000000..3f16564 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/PointStateVarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.953593 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.PointStateVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVarTs.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 reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.PointStateVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.PointStateVarTs" +#define reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.PointStateVarTs.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 reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_EXTENT_BYTES_ 67UL +#define reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 67UL +static_assert(reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.geodetic.PointStateVar.0.1 value + reg_udral_physics_kinematics_geodetic_PointStateVar_0_1 value; +} reg_udral_physics_kinematics_geodetic_PointStateVarTs_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 reg_udral_physics_kinematics_geodetic_PointStateVarTs_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 reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_PointStateVarTs_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) < 536UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.geodetic.PointStateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 480ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 60UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 480ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 536ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_PointStateVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.geodetic.PointStateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_initialize_(reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/PointStateVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/PointStateVar_0_1.h new file mode 100644 index 0000000..ce42209 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/PointStateVar_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.950393 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.PointStateVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointStateVar.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 reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.PointStateVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.PointStateVar" +#define reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.PointStateVar.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 reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_EXTENT_BYTES_ 60UL +#define reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 60UL +static_assert(reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.PointVar.0.1 position + reg_udral_physics_kinematics_geodetic_PointVar_0_1 position; + + /// reg.udral.physics.kinematics.translation.Velocity3Var.0.2 velocity + reg_udral_physics_kinematics_translation_Velocity3Var_0_2 velocity; +} reg_udral_physics_kinematics_geodetic_PointStateVar_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 reg_udral_physics_kinematics_geodetic_PointStateVar_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 reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_PointStateVar_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) < 480UL) + { + 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; + { // reg.udral.physics.kinematics.geodetic.PointVar.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 288ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 36UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_PointVar_0_1_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 288ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.translation.Velocity3Var.0.2 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_translation_Velocity3Var_0_2_serialize_( + &obj->velocity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 192ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 480ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_PointStateVar_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; + // reg.udral.physics.kinematics.geodetic.PointVar.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_geodetic_PointVar_0_1_deserialize_( + &out_obj->position, &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. + // reg.udral.physics.kinematics.translation.Velocity3Var.0.2 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_translation_Velocity3Var_0_2_deserialize_( + &out_obj->velocity, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_initialize_(reg_udral_physics_kinematics_geodetic_PointStateVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_PointStateVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/PointState_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/PointState_0_1.h new file mode 100644 index 0000000..784924a --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/PointState_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointState.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.947156 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.PointState +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointState.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointState.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointState.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointState.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointState.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 reg_udral_physics_kinematics_geodetic_PointState_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.PointState.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_PointState_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.PointState" +#define reg_udral_physics_kinematics_geodetic_PointState_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.PointState.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 reg_udral_physics_kinematics_geodetic_PointState_0_1_EXTENT_BYTES_ 36UL +#define reg_udral_physics_kinematics_geodetic_PointState_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 36UL +static_assert(reg_udral_physics_kinematics_geodetic_PointState_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_PointState_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.Point.0.1 position + reg_udral_physics_kinematics_geodetic_Point_0_1 position; + + /// uavcan.si.unit.velocity.Vector3.1.0 velocity + uavcan_si_unit_velocity_Vector3_1_0 velocity; +} reg_udral_physics_kinematics_geodetic_PointState_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 reg_udral_physics_kinematics_geodetic_PointState_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 reg_udral_physics_kinematics_geodetic_PointState_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_PointState_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) < 288UL) + { + 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; + { // reg.udral.physics.kinematics.geodetic.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_Point_0_1_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.velocity.Vector3.1.0 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_velocity_Vector3_1_0_serialize_( + &obj->velocity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 96ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 288ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_PointState_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_PointState_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; + // reg.udral.physics.kinematics.geodetic.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_geodetic_Point_0_1_deserialize_( + &out_obj->position, &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.si.unit.velocity.Vector3.1.0 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_velocity_Vector3_1_0_deserialize_( + &out_obj->velocity, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_PointState_0_1_initialize_(reg_udral_physics_kinematics_geodetic_PointState_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_PointState_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_STATE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/PointVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/PointVar_0_1.h new file mode 100644 index 0000000..fb29259 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/PointVar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.956849 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.PointVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PointVar.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 reg_udral_physics_kinematics_geodetic_PointVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.PointVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_PointVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.PointVar" +#define reg_udral_physics_kinematics_geodetic_PointVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.PointVar.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 reg_udral_physics_kinematics_geodetic_PointVar_0_1_EXTENT_BYTES_ 36UL +#define reg_udral_physics_kinematics_geodetic_PointVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 36UL +static_assert(reg_udral_physics_kinematics_geodetic_PointVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_PointVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[6] covariance_urt +#define reg_udral_physics_kinematics_geodetic_PointVar_0_1_covariance_urt_ARRAY_CAPACITY_ 6U +#define reg_udral_physics_kinematics_geodetic_PointVar_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.Point.0.1 value + reg_udral_physics_kinematics_geodetic_Point_0_1 value; + + /// saturated float16[6] covariance_urt + float covariance_urt[6]; +} reg_udral_physics_kinematics_geodetic_PointVar_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 reg_udral_physics_kinematics_geodetic_PointVar_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 reg_udral_physics_kinematics_geodetic_PointVar_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_PointVar_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) < 288UL) + { + 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; + { // reg.udral.physics.kinematics.geodetic.Point.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_Point_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 288ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_PointVar_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_PointVar_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; + // reg.udral.physics.kinematics.geodetic.Point.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = reg_udral_physics_kinematics_geodetic_Point_0_1_deserialize_( + &out_obj->value, &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 float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_PointVar_0_1_initialize_(reg_udral_physics_kinematics_geodetic_PointVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_PointVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/Point_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/Point_0_1.h new file mode 100644 index 0000000..ef59a65 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/Point_0_1.h @@ -0,0 +1,281 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Point.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.943722 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.Point +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Point.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Point.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Point.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Point.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Point.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 reg_udral_physics_kinematics_geodetic_Point_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.Point.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_Point_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.Point" +#define reg_udral_physics_kinematics_geodetic_Point_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.Point.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 reg_udral_physics_kinematics_geodetic_Point_0_1_EXTENT_BYTES_ 24UL +#define reg_udral_physics_kinematics_geodetic_Point_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 24UL +static_assert(reg_udral_physics_kinematics_geodetic_Point_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_Point_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float64 latitude + double latitude; + + /// saturated float64 longitude + double longitude; + + /// uavcan.si.unit.length.WideScalar.1.0 altitude + uavcan_si_unit_length_WideScalar_1_0 altitude; +} reg_udral_physics_kinematics_geodetic_Point_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 reg_udral_physics_kinematics_geodetic_Point_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 reg_udral_physics_kinematics_geodetic_Point_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_Point_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) < 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 latitude + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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->latitude); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 64U; + } + { // saturated float64 longitude + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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->longitude); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.length.WideScalar.1.0 altitude + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 8UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err3_ = uavcan_si_unit_length_WideScalar_1_0_serialize_( + &obj->altitude, &buffer[offset_bits / 8U], &_size_bytes0_); + 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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 64ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 192ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_Point_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_Point_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 float64 latitude + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->latitude = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + // saturated float64 longitude + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->longitude = nunavutGetF64(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.length.WideScalar.1.0 altitude + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_length_WideScalar_1_0_deserialize_( + &out_obj->altitude, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err5_ < 0) + { + return _err5_; + } + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_Point_0_1_initialize_(reg_udral_physics_kinematics_geodetic_Point_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_Point_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POINT_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/PoseVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/PoseVar_0_1.h new file mode 100644 index 0000000..c09fa92 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/PoseVar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PoseVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.963322 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.PoseVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POSE_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POSE_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PoseVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PoseVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PoseVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PoseVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/PoseVar.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 reg_udral_physics_kinematics_geodetic_PoseVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.PoseVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_PoseVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.PoseVar" +#define reg_udral_physics_kinematics_geodetic_PoseVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.PoseVar.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 reg_udral_physics_kinematics_geodetic_PoseVar_0_1_EXTENT_BYTES_ 82UL +#define reg_udral_physics_kinematics_geodetic_PoseVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 82UL +static_assert(reg_udral_physics_kinematics_geodetic_PoseVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_PoseVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[21] covariance_urt +#define reg_udral_physics_kinematics_geodetic_PoseVar_0_1_covariance_urt_ARRAY_CAPACITY_ 21U +#define reg_udral_physics_kinematics_geodetic_PoseVar_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.Pose.0.1 value + reg_udral_physics_kinematics_geodetic_Pose_0_1 value; + + /// saturated float16[21] covariance_urt + float covariance_urt[21]; +} reg_udral_physics_kinematics_geodetic_PoseVar_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 reg_udral_physics_kinematics_geodetic_PoseVar_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 reg_udral_physics_kinematics_geodetic_PoseVar_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_PoseVar_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) < 656UL) + { + 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; + { // reg.udral.physics.kinematics.geodetic.Pose.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 320ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 40UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_Pose_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 320ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[21] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 336ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 21UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 336ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 656ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_PoseVar_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_PoseVar_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; + // reg.udral.physics.kinematics.geodetic.Pose.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = reg_udral_physics_kinematics_geodetic_Pose_0_1_deserialize_( + &out_obj->value, &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 float16[21] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 21UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_PoseVar_0_1_initialize_(reg_udral_physics_kinematics_geodetic_PoseVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_PoseVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POSE_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/Pose_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/Pose_0_1.h new file mode 100644 index 0000000..86a01dd --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/Pose_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Pose.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.960080 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.Pose +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POSE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POSE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Pose.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Pose.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Pose.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Pose.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/Pose.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 reg_udral_physics_kinematics_geodetic_Pose_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.Pose.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_Pose_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.Pose" +#define reg_udral_physics_kinematics_geodetic_Pose_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.Pose.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 reg_udral_physics_kinematics_geodetic_Pose_0_1_EXTENT_BYTES_ 40UL +#define reg_udral_physics_kinematics_geodetic_Pose_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 40UL +static_assert(reg_udral_physics_kinematics_geodetic_Pose_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_Pose_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.Point.0.1 position + reg_udral_physics_kinematics_geodetic_Point_0_1 position; + + /// uavcan.si.unit.angle.Quaternion.1.0 orientation + uavcan_si_unit_angle_Quaternion_1_0 orientation; +} reg_udral_physics_kinematics_geodetic_Pose_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 reg_udral_physics_kinematics_geodetic_Pose_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 reg_udral_physics_kinematics_geodetic_Pose_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_Pose_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) < 320UL) + { + 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; + { // reg.udral.physics.kinematics.geodetic.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_Point_0_1_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 192ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.angle.Quaternion.1.0 orientation + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 16UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_angle_Quaternion_1_0_serialize_( + &obj->orientation, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 128ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 320ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_Pose_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_Pose_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; + // reg.udral.physics.kinematics.geodetic.Point.0.1 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_geodetic_Point_0_1_deserialize_( + &out_obj->position, &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.si.unit.angle.Quaternion.1.0 orientation + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_angle_Quaternion_1_0_deserialize_( + &out_obj->orientation, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_Pose_0_1_initialize_(reg_udral_physics_kinematics_geodetic_Pose_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_Pose_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_POSE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/StateVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/StateVarTs_0_1.h new file mode 100644 index 0000000..cc2ae6f --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/StateVarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.973094 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.StateVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVarTs.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 reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.StateVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.StateVarTs" +#define reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.StateVarTs.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 reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_EXTENT_BYTES_ 155UL +#define reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 155UL +static_assert(reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.geodetic.StateVar.0.1 value + reg_udral_physics_kinematics_geodetic_StateVar_0_1 value; +} reg_udral_physics_kinematics_geodetic_StateVarTs_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 reg_udral_physics_kinematics_geodetic_StateVarTs_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 reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_StateVarTs_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) < 1240UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.geodetic.StateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1184ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 148UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_geodetic_StateVar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 1184ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 1240ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_StateVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.geodetic.StateVar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_geodetic_StateVar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_initialize_(reg_udral_physics_kinematics_geodetic_StateVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_StateVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/StateVar_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/StateVar_0_1.h new file mode 100644 index 0000000..cf17e2c --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/StateVar_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVar.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.969755 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.StateVar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/StateVar.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 reg_udral_physics_kinematics_geodetic_StateVar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.StateVar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_StateVar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.StateVar" +#define reg_udral_physics_kinematics_geodetic_StateVar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.StateVar.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 reg_udral_physics_kinematics_geodetic_StateVar_0_1_EXTENT_BYTES_ 148UL +#define reg_udral_physics_kinematics_geodetic_StateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 148UL +static_assert(reg_udral_physics_kinematics_geodetic_StateVar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_StateVar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.PoseVar.0.1 pose + reg_udral_physics_kinematics_geodetic_PoseVar_0_1 pose; + + /// reg.udral.physics.kinematics.cartesian.TwistVar.0.1 twist + reg_udral_physics_kinematics_cartesian_TwistVar_0_1 twist; +} reg_udral_physics_kinematics_geodetic_StateVar_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 reg_udral_physics_kinematics_geodetic_StateVar_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 reg_udral_physics_kinematics_geodetic_StateVar_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_StateVar_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) < 1184UL) + { + 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; + { // reg.udral.physics.kinematics.geodetic.PoseVar.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 656ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 82UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_PoseVar_0_1_serialize_( + &obj->pose, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 656ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.TwistVar.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 528ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 66UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_serialize_( + &obj->twist, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 528ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 1184ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_StateVar_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_StateVar_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; + // reg.udral.physics.kinematics.geodetic.PoseVar.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_geodetic_PoseVar_0_1_deserialize_( + &out_obj->pose, &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. + // reg.udral.physics.kinematics.cartesian.TwistVar.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_TwistVar_0_1_deserialize_( + &out_obj->twist, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_StateVar_0_1_initialize_(reg_udral_physics_kinematics_geodetic_StateVar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_StateVar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/geodetic/State_0_1.h b/hardware/include/reg/udral/physics/kinematics/geodetic/State_0_1.h new file mode 100644 index 0000000..020dca2 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/geodetic/State_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/State.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.966515 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.geodetic.State +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/State.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/State.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/State.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/State.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/geodetic/State.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 reg_udral_physics_kinematics_geodetic_State_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.geodetic.State.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_geodetic_State_0_1_FULL_NAME_ "reg.udral.physics.kinematics.geodetic.State" +#define reg_udral_physics_kinematics_geodetic_State_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.geodetic.State.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 reg_udral_physics_kinematics_geodetic_State_0_1_EXTENT_BYTES_ 64UL +#define reg_udral_physics_kinematics_geodetic_State_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 64UL +static_assert(reg_udral_physics_kinematics_geodetic_State_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_geodetic_State_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.geodetic.Pose.0.1 pose + reg_udral_physics_kinematics_geodetic_Pose_0_1 pose; + + /// reg.udral.physics.kinematics.cartesian.Twist.0.1 twist + reg_udral_physics_kinematics_cartesian_Twist_0_1 twist; +} reg_udral_physics_kinematics_geodetic_State_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 reg_udral_physics_kinematics_geodetic_State_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 reg_udral_physics_kinematics_geodetic_State_0_1_serialize_( + const reg_udral_physics_kinematics_geodetic_State_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; + { // reg.udral.physics.kinematics.geodetic.Pose.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 320ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 40UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_geodetic_Pose_0_1_serialize_( + &obj->pose, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 320ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.cartesian.Twist.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 24UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_cartesian_Twist_0_1_serialize_( + &obj->twist, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 192ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 512ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_geodetic_State_0_1_deserialize_( + reg_udral_physics_kinematics_geodetic_State_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; + // reg.udral.physics.kinematics.geodetic.Pose.0.1 pose + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_physics_kinematics_geodetic_Pose_0_1_deserialize_( + &out_obj->pose, &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. + // reg.udral.physics.kinematics.cartesian.Twist.0.1 twist + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_cartesian_Twist_0_1_deserialize_( + &out_obj->twist, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_geodetic_State_0_1_initialize_(reg_udral_physics_kinematics_geodetic_State_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_geodetic_State_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_GEODETIC_STATE_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/rotation/PlanarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/rotation/PlanarTs_0_1.h new file mode 100644 index 0000000..aeabebf --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/rotation/PlanarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/PlanarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.000201 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.rotation.PlanarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_ROTATION_PLANAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_ROTATION_PLANAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/PlanarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/PlanarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/PlanarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/PlanarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/PlanarTs.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 reg_udral_physics_kinematics_rotation_PlanarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.rotation.PlanarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_rotation_PlanarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.rotation.PlanarTs" +#define reg_udral_physics_kinematics_rotation_PlanarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.rotation.PlanarTs.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 reg_udral_physics_kinematics_rotation_PlanarTs_0_1_EXTENT_BYTES_ 19UL +#define reg_udral_physics_kinematics_rotation_PlanarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(reg_udral_physics_kinematics_rotation_PlanarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_rotation_PlanarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.rotation.Planar.0.1 value + reg_udral_physics_kinematics_rotation_Planar_0_1 value; +} reg_udral_physics_kinematics_rotation_PlanarTs_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 reg_udral_physics_kinematics_rotation_PlanarTs_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 reg_udral_physics_kinematics_rotation_PlanarTs_0_1_serialize_( + const reg_udral_physics_kinematics_rotation_PlanarTs_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.rotation.Planar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_rotation_Planar_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 96ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_rotation_PlanarTs_0_1_deserialize_( + reg_udral_physics_kinematics_rotation_PlanarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.rotation.Planar.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_rotation_Planar_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_rotation_PlanarTs_0_1_initialize_(reg_udral_physics_kinematics_rotation_PlanarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_rotation_PlanarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_ROTATION_PLANAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/rotation/Planar_0_1.h b/hardware/include/reg/udral/physics/kinematics/rotation/Planar_0_1.h new file mode 100644 index 0000000..27cab27 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/rotation/Planar_0_1.h @@ -0,0 +1,328 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/Planar.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.996395 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.rotation.Planar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_ROTATION_PLANAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_ROTATION_PLANAR_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/Planar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/Planar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/Planar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/Planar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/rotation/Planar.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 reg_udral_physics_kinematics_rotation_Planar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.rotation.Planar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_rotation_Planar_0_1_FULL_NAME_ "reg.udral.physics.kinematics.rotation.Planar" +#define reg_udral_physics_kinematics_rotation_Planar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.rotation.Planar.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 reg_udral_physics_kinematics_rotation_Planar_0_1_EXTENT_BYTES_ 12UL +#define reg_udral_physics_kinematics_rotation_Planar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(reg_udral_physics_kinematics_rotation_Planar_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_rotation_Planar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.angle.Scalar.1.0 angular_position + uavcan_si_unit_angle_Scalar_1_0 angular_position; + + /// uavcan.si.unit.angular_velocity.Scalar.1.0 angular_velocity + uavcan_si_unit_angular_velocity_Scalar_1_0 angular_velocity; + + /// uavcan.si.unit.angular_acceleration.Scalar.1.0 angular_acceleration + uavcan_si_unit_angular_acceleration_Scalar_1_0 angular_acceleration; +} reg_udral_physics_kinematics_rotation_Planar_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 reg_udral_physics_kinematics_rotation_Planar_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 reg_udral_physics_kinematics_rotation_Planar_0_1_serialize_( + const reg_udral_physics_kinematics_rotation_Planar_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) < 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; + { // uavcan.si.unit.angle.Scalar.1.0 angular_position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_angle_Scalar_1_0_serialize_( + &obj->angular_position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.angular_velocity.Scalar.1.0 angular_velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_angular_velocity_Scalar_1_0_serialize_( + &obj->angular_velocity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.angular_acceleration.Scalar.1.0 angular_acceleration + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_angular_acceleration_Scalar_1_0_serialize_( + &obj->angular_acceleration, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_rotation_Planar_0_1_deserialize_( + reg_udral_physics_kinematics_rotation_Planar_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.si.unit.angle.Scalar.1.0 angular_position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err6_ = uavcan_si_unit_angle_Scalar_1_0_deserialize_( + &out_obj->angular_position, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err6_ < 0) + { + return _err6_; + } + 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.si.unit.angular_velocity.Scalar.1.0 angular_velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err7_ = uavcan_si_unit_angular_velocity_Scalar_1_0_deserialize_( + &out_obj->angular_velocity, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err7_ < 0) + { + return _err7_; + } + 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.si.unit.angular_acceleration.Scalar.1.0 angular_acceleration + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err8_ = uavcan_si_unit_angular_acceleration_Scalar_1_0_deserialize_( + &out_obj->angular_acceleration, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err8_ < 0) + { + return _err8_; + } + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_rotation_Planar_0_1_initialize_(reg_udral_physics_kinematics_rotation_Planar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_rotation_Planar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_ROTATION_PLANAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/translation/LinearTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/translation/LinearTs_0_1.h new file mode 100644 index 0000000..8ede5df --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/translation/LinearTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.980007 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.translation.LinearTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearTs.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 reg_udral_physics_kinematics_translation_LinearTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.translation.LinearTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_translation_LinearTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.translation.LinearTs" +#define reg_udral_physics_kinematics_translation_LinearTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.translation.LinearTs.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 reg_udral_physics_kinematics_translation_LinearTs_0_1_EXTENT_BYTES_ 19UL +#define reg_udral_physics_kinematics_translation_LinearTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(reg_udral_physics_kinematics_translation_LinearTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_translation_LinearTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.kinematics.translation.Linear.0.1 value + reg_udral_physics_kinematics_translation_Linear_0_1 value; +} reg_udral_physics_kinematics_translation_LinearTs_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 reg_udral_physics_kinematics_translation_LinearTs_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 reg_udral_physics_kinematics_translation_LinearTs_0_1_serialize_( + const reg_udral_physics_kinematics_translation_LinearTs_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.kinematics.translation.Linear.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_kinematics_translation_Linear_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 96ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_translation_LinearTs_0_1_deserialize_( + reg_udral_physics_kinematics_translation_LinearTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.kinematics.translation.Linear.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_translation_Linear_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_translation_LinearTs_0_1_initialize_(reg_udral_physics_kinematics_translation_LinearTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_translation_LinearTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/translation/LinearVarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/translation/LinearVarTs_0_1.h new file mode 100644 index 0000000..0d6a04c --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/translation/LinearVarTs_0_1.h @@ -0,0 +1,317 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.983073 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.translation.LinearVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/LinearVarTs.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 reg_udral_physics_kinematics_translation_LinearVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.translation.LinearVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_translation_LinearVarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.translation.LinearVarTs" +#define reg_udral_physics_kinematics_translation_LinearVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.translation.LinearVarTs.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 reg_udral_physics_kinematics_translation_LinearVarTs_0_1_EXTENT_BYTES_ 25UL +#define reg_udral_physics_kinematics_translation_LinearVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 25UL +static_assert(reg_udral_physics_kinematics_translation_LinearVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_translation_LinearVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.kinematics.translation.LinearTs.0.1 value + reg_udral_physics_kinematics_translation_LinearTs_0_1 value; + + /// saturated float16 position_error_variance + float position_error_variance; + + /// saturated float16 velocity_error_variance + float velocity_error_variance; + + /// saturated float16 acceleration_error_variance + float acceleration_error_variance; +} reg_udral_physics_kinematics_translation_LinearVarTs_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 reg_udral_physics_kinematics_translation_LinearVarTs_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 reg_udral_physics_kinematics_translation_LinearVarTs_0_1_serialize_( + const reg_udral_physics_kinematics_translation_LinearVarTs_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) < 200UL) + { + 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; + { // reg.udral.physics.kinematics.translation.LinearTs.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 152ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 19UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_kinematics_translation_LinearTs_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 152ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16 position_error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->position_error_variance; + if (isfinite(_sat0_)) + { + if (_sat0_ < ((float) -65504.0)) + { + _sat0_ = ((float) -65504.0); + } + if (_sat0_ > ((float) 65504.0)) + { + _sat0_ = ((float) 65504.0); + } + } + const int8_t _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + { // saturated float16 velocity_error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat1_ = obj->velocity_error_variance; + if (isfinite(_sat1_)) + { + if (_sat1_ < ((float) -65504.0)) + { + _sat1_ = ((float) -65504.0); + } + if (_sat1_ > ((float) 65504.0)) + { + _sat1_ = ((float) 65504.0); + } + } + const int8_t _err2_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat1_); + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += 16U; + } + { // saturated float16 acceleration_error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat2_ = obj->acceleration_error_variance; + if (isfinite(_sat2_)) + { + if (_sat2_ < ((float) -65504.0)) + { + _sat2_ = ((float) -65504.0); + } + if (_sat2_ > ((float) 65504.0)) + { + _sat2_ = ((float) 65504.0); + } + } + const int8_t _err3_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat2_); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 200ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_translation_LinearVarTs_0_1_deserialize_( + reg_udral_physics_kinematics_translation_LinearVarTs_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; + // reg.udral.physics.kinematics.translation.LinearTs.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_kinematics_translation_LinearTs_0_1_deserialize_( + &out_obj->value, &buffer[offset_bits / 8U], &_size_bytes1_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated float16 position_error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->position_error_variance = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + // saturated float16 velocity_error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->velocity_error_variance = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + // saturated float16 acceleration_error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->acceleration_error_variance = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_translation_LinearVarTs_0_1_initialize_(reg_udral_physics_kinematics_translation_LinearVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_translation_LinearVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/translation/Linear_0_1.h b/hardware/include/reg/udral/physics/kinematics/translation/Linear_0_1.h new file mode 100644 index 0000000..83c932d --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/translation/Linear_0_1.h @@ -0,0 +1,328 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Linear.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.976261 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.translation.Linear +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Linear.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Linear.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Linear.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Linear.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Linear.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 reg_udral_physics_kinematics_translation_Linear_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.translation.Linear.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_translation_Linear_0_1_FULL_NAME_ "reg.udral.physics.kinematics.translation.Linear" +#define reg_udral_physics_kinematics_translation_Linear_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.translation.Linear.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 reg_udral_physics_kinematics_translation_Linear_0_1_EXTENT_BYTES_ 12UL +#define reg_udral_physics_kinematics_translation_Linear_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(reg_udral_physics_kinematics_translation_Linear_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_translation_Linear_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.length.Scalar.1.0 position + uavcan_si_unit_length_Scalar_1_0 position; + + /// uavcan.si.unit.velocity.Scalar.1.0 velocity + uavcan_si_unit_velocity_Scalar_1_0 velocity; + + /// uavcan.si.unit.acceleration.Scalar.1.0 acceleration + uavcan_si_unit_acceleration_Scalar_1_0 acceleration; +} reg_udral_physics_kinematics_translation_Linear_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 reg_udral_physics_kinematics_translation_Linear_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 reg_udral_physics_kinematics_translation_Linear_0_1_serialize_( + const reg_udral_physics_kinematics_translation_Linear_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) < 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; + { // uavcan.si.unit.length.Scalar.1.0 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_length_Scalar_1_0_serialize_( + &obj->position, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.velocity.Scalar.1.0 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_velocity_Scalar_1_0_serialize_( + &obj->velocity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.acceleration.Scalar.1.0 acceleration + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_acceleration_Scalar_1_0_serialize_( + &obj->acceleration, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_translation_Linear_0_1_deserialize_( + reg_udral_physics_kinematics_translation_Linear_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.si.unit.length.Scalar.1.0 position + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err6_ = uavcan_si_unit_length_Scalar_1_0_deserialize_( + &out_obj->position, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err6_ < 0) + { + return _err6_; + } + 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.si.unit.velocity.Scalar.1.0 velocity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err7_ = uavcan_si_unit_velocity_Scalar_1_0_deserialize_( + &out_obj->velocity, &buffer[offset_bits / 8U], &_size_bytes4_); + if (_err7_ < 0) + { + return _err7_; + } + 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.si.unit.acceleration.Scalar.1.0 acceleration + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err8_ = uavcan_si_unit_acceleration_Scalar_1_0_deserialize_( + &out_obj->acceleration, &buffer[offset_bits / 8U], &_size_bytes5_); + if (_err8_ < 0) + { + return _err8_; + } + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_translation_Linear_0_1_initialize_(reg_udral_physics_kinematics_translation_Linear_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_translation_Linear_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_LINEAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/translation/Velocity1VarTs_0_1.h b/hardware/include/reg/udral/physics/kinematics/translation/Velocity1VarTs_0_1.h new file mode 100644 index 0000000..f82c137 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/translation/Velocity1VarTs_0_1.h @@ -0,0 +1,259 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity1VarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.986822 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.translation.Velocity1VarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY1VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY1VAR_TS_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity1VarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity1VarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity1VarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity1VarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity1VarTs.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 reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.translation.Velocity1VarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_FULL_NAME_ "reg.udral.physics.kinematics.translation.Velocity1VarTs" +#define reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.translation.Velocity1VarTs.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 reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_EXTENT_BYTES_ 13UL +#define reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 13UL +static_assert(reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.sample.velocity.Scalar.1.0 value + uavcan_si_sample_velocity_Scalar_1_0 value; + + /// saturated float16 error_variance + float error_variance; +} reg_udral_physics_kinematics_translation_Velocity1VarTs_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 reg_udral_physics_kinematics_translation_Velocity1VarTs_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 reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_serialize_( + const reg_udral_physics_kinematics_translation_Velocity1VarTs_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.si.sample.velocity.Scalar.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 88ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 11UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_sample_velocity_Scalar_1_0_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 88ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16 error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->error_variance; + if (isfinite(_sat0_)) + { + if (_sat0_ < ((float) -65504.0)) + { + _sat0_ = ((float) -65504.0); + } + if (_sat0_ > ((float) 65504.0)) + { + _sat0_ = ((float) 65504.0); + } + } + const int8_t _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 104ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_deserialize_( + reg_udral_physics_kinematics_translation_Velocity1VarTs_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.si.sample.velocity.Scalar.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = uavcan_si_sample_velocity_Scalar_1_0_deserialize_( + &out_obj->value, &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 float16 error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->error_variance = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_initialize_(reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_translation_Velocity1VarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY1VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/translation/Velocity3Var_0_1.h b/hardware/include/reg/udral/physics/kinematics/translation/Velocity3Var_0_1.h new file mode 100644 index 0000000..3d53c1f --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/translation/Velocity3Var_0_1.h @@ -0,0 +1,286 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.993113 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.translation.Velocity3Var +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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 REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY3VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY3VAR_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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 reg_udral_physics_kinematics_translation_Velocity3Var_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.translation.Velocity3Var.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_1_FULL_NAME_ "reg.udral.physics.kinematics.translation.Velocity3Var" +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.translation.Velocity3Var.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 reg_udral_physics_kinematics_translation_Velocity3Var_0_1_EXTENT_BYTES_ 31UL +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 31UL +static_assert(reg_udral_physics_kinematics_translation_Velocity3Var_0_1_EXTENT_BYTES_ >= reg_udral_physics_kinematics_translation_Velocity3Var_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[6] covariance_urt +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_1_covariance_urt_ARRAY_CAPACITY_ 6U +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.si.sample.velocity.Vector3.1.0 value + uavcan_si_sample_velocity_Vector3_1_0 value; + + /// saturated float16[6] covariance_urt + float covariance_urt[6]; +} reg_udral_physics_kinematics_translation_Velocity3Var_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 reg_udral_physics_kinematics_translation_Velocity3Var_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 reg_udral_physics_kinematics_translation_Velocity3Var_0_1_serialize_( + const reg_udral_physics_kinematics_translation_Velocity3Var_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) < 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.si.sample.velocity.Vector3.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 152ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 19UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_sample_velocity_Vector3_1_0_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 152ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 248ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_translation_Velocity3Var_0_1_deserialize_( + reg_udral_physics_kinematics_translation_Velocity3Var_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.si.sample.velocity.Vector3.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = uavcan_si_sample_velocity_Vector3_1_0_deserialize_( + &out_obj->value, &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 float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_translation_Velocity3Var_0_1_initialize_(reg_udral_physics_kinematics_translation_Velocity3Var_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_translation_Velocity3Var_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY3VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/kinematics/translation/Velocity3Var_0_2.h b/hardware/include/reg/udral/physics/kinematics/translation/Velocity3Var_0_2.h new file mode 100644 index 0000000..ae84094 --- /dev/null +++ b/hardware/include/reg/udral/physics/kinematics/translation/Velocity3Var_0_2.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.0.2.dsdl +// Generated at: 2025-07-17 18:00:16.989978 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.kinematics.translation.Velocity3Var +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY3VAR_0_2_INCLUDED_ +#define REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY3VAR_0_2_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/kinematics/translation/Velocity3Var.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 reg_udral_physics_kinematics_translation_Velocity3Var_0_2_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.kinematics.translation.Velocity3Var.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_2_FULL_NAME_ "reg.udral.physics.kinematics.translation.Velocity3Var" +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_2_FULL_NAME_AND_VERSION_ "reg.udral.physics.kinematics.translation.Velocity3Var.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 reg_udral_physics_kinematics_translation_Velocity3Var_0_2_EXTENT_BYTES_ 24UL +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 24UL +static_assert(reg_udral_physics_kinematics_translation_Velocity3Var_0_2_EXTENT_BYTES_ >= reg_udral_physics_kinematics_translation_Velocity3Var_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[6] covariance_urt +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_2_covariance_urt_ARRAY_CAPACITY_ 6U +#define reg_udral_physics_kinematics_translation_Velocity3Var_0_2_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.si.unit.velocity.Vector3.1.0 value + uavcan_si_unit_velocity_Vector3_1_0 value; + + /// saturated float16[6] covariance_urt + float covariance_urt[6]; +} reg_udral_physics_kinematics_translation_Velocity3Var_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 reg_udral_physics_kinematics_translation_Velocity3Var_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 reg_udral_physics_kinematics_translation_Velocity3Var_0_2_serialize_( + const reg_udral_physics_kinematics_translation_Velocity3Var_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) < 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; + { // uavcan.si.unit.velocity.Vector3.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_velocity_Vector3_1_0_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 96ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err1_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 192ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_kinematics_translation_Velocity3Var_0_2_deserialize_( + reg_udral_physics_kinematics_translation_Velocity3Var_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.si.unit.velocity.Vector3.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = uavcan_si_unit_velocity_Vector3_1_0_deserialize_( + &out_obj->value, &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 float16[6] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_kinematics_translation_Velocity3Var_0_2_initialize_(reg_udral_physics_kinematics_translation_Velocity3Var_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_kinematics_translation_Velocity3Var_0_2_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_KINEMATICS_TRANSLATION_VELOCITY3VAR_0_2_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/optics/HighColor_0_1.h b/hardware/include/reg/udral/physics/optics/HighColor_0_1.h new file mode 100644 index 0000000..0a71ce1 --- /dev/null +++ b/hardware/include/reg/udral/physics/optics/HighColor_0_1.h @@ -0,0 +1,269 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/optics/HighColor.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.090452 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.optics.HighColor +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_OPTICS_HIGH_COLOR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_OPTICS_HIGH_COLOR_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/optics/HighColor.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/optics/HighColor.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/optics/HighColor.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/optics/HighColor.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/optics/HighColor.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 reg_udral_physics_optics_HighColor_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.optics.HighColor.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_optics_HighColor_0_1_FULL_NAME_ "reg.udral.physics.optics.HighColor" +#define reg_udral_physics_optics_HighColor_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.optics.HighColor.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 reg_udral_physics_optics_HighColor_0_1_EXTENT_BYTES_ 2UL +#define reg_udral_physics_optics_HighColor_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(reg_udral_physics_optics_HighColor_0_1_EXTENT_BYTES_ >= reg_udral_physics_optics_HighColor_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint5 MAX_RED = 31 +#define reg_udral_physics_optics_HighColor_0_1_MAX_RED (31U) + +/// saturated uint6 MAX_GREEN = 63 +#define reg_udral_physics_optics_HighColor_0_1_MAX_GREEN (63U) + +/// saturated uint5 MAX_BLUE = 31 +#define reg_udral_physics_optics_HighColor_0_1_MAX_BLUE (31U) + +typedef struct +{ + /// saturated uint5 red + uint8_t red; + + /// saturated uint6 green + uint8_t green; + + /// saturated uint5 blue + uint8_t blue; +} reg_udral_physics_optics_HighColor_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 reg_udral_physics_optics_HighColor_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 reg_udral_physics_optics_HighColor_0_1_serialize_( + const reg_udral_physics_optics_HighColor_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 uint5 red + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 5ULL) <= (capacity_bytes * 8U)); + uint8_t _sat0_ = obj->red; + if (_sat0_ > 31U) + { + _sat0_ = 31U; + } + buffer[offset_bits / 8U] = (uint8_t)(_sat0_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 5U; + } + { // saturated uint6 green + NUNAVUT_ASSERT((offset_bits + 6ULL) <= (capacity_bytes * 8U)); + uint8_t _sat1_ = obj->green; + if (_sat1_ > 63U) + { + _sat1_ = 63U; + } + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _sat1_, 6U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 6U; + } + { // saturated uint5 blue + NUNAVUT_ASSERT((offset_bits + 5ULL) <= (capacity_bytes * 8U)); + uint8_t _sat2_ = obj->blue; + if (_sat2_ > 31U) + { + _sat2_ = 31U; + } + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, _sat2_, 5U); + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += 5U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_optics_HighColor_0_1_deserialize_( + reg_udral_physics_optics_HighColor_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 uint5 red + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + if ((offset_bits + 5U) <= capacity_bits) + { + out_obj->red = buffer[offset_bits / 8U] & 31U; + } + else + { + out_obj->red = 0U; + } + offset_bits += 5U; + // saturated uint6 green + out_obj->green = nunavutGetU8(&buffer[0], capacity_bytes, offset_bits, 6); + offset_bits += 6U; + // saturated uint5 blue + out_obj->blue = nunavutGetU8(&buffer[0], capacity_bytes, offset_bits, 5); + offset_bits += 5U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_optics_HighColor_0_1_initialize_(reg_udral_physics_optics_HighColor_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_optics_HighColor_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_OPTICS_HIGH_COLOR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/thermodynamics/PressureTempVarTs_0_1.h b/hardware/include/reg/udral/physics/thermodynamics/PressureTempVarTs_0_1.h new file mode 100644 index 0000000..897fa3c --- /dev/null +++ b/hardware/include/reg/udral/physics/thermodynamics/PressureTempVarTs_0_1.h @@ -0,0 +1,375 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/thermodynamics/PressureTempVarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.072518 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.thermodynamics.PressureTempVarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_THERMODYNAMICS_PRESSURE_TEMP_VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_THERMODYNAMICS_PRESSURE_TEMP_VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/thermodynamics/PressureTempVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/thermodynamics/PressureTempVarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/thermodynamics/PressureTempVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/thermodynamics/PressureTempVarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/thermodynamics/PressureTempVarTs.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 reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.thermodynamics.PressureTempVarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_FULL_NAME_ "reg.udral.physics.thermodynamics.PressureTempVarTs" +#define reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.thermodynamics.PressureTempVarTs.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 reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_EXTENT_BYTES_ 21UL +#define reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 21UL +static_assert(reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[3] covariance_urt +#define reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_covariance_urt_ARRAY_CAPACITY_ 3U +#define reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_covariance_urt_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// uavcan.si.unit.pressure.Scalar.1.0 pressure + uavcan_si_unit_pressure_Scalar_1_0 pressure; + + /// uavcan.si.unit.temperature.Scalar.1.0 temperature + uavcan_si_unit_temperature_Scalar_1_0 temperature; + + /// saturated float16[3] covariance_urt + float covariance_urt[3]; +} reg_udral_physics_thermodynamics_PressureTempVarTs_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 reg_udral_physics_thermodynamics_PressureTempVarTs_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 reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_serialize_( + const reg_udral_physics_thermodynamics_PressureTempVarTs_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) < 168UL) + { + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.pressure.Scalar.1.0 pressure + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_pressure_Scalar_1_0_serialize_( + &obj->pressure, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.temperature.Scalar.1.0 temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_temperature_Scalar_1_0_serialize_( + &obj->temperature, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[3] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 48ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->covariance_urt[_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 _err5_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += 16U; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 48ULL); + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad2_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 168ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_deserialize_( + reg_udral_physics_thermodynamics_PressureTempVarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.pressure.Scalar.1.0 pressure + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err8_ = uavcan_si_unit_pressure_Scalar_1_0_deserialize_( + &out_obj->pressure, &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.si.unit.temperature.Scalar.1.0 temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err9_ = uavcan_si_unit_temperature_Scalar_1_0_deserialize_( + &out_obj->temperature, &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 float16[3] covariance_urt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->covariance_urt[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_initialize_(reg_udral_physics_thermodynamics_PressureTempVarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_thermodynamics_PressureTempVarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_THERMODYNAMICS_PRESSURE_TEMP_VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/time/TAI64VarTs_0_1.h b/hardware/include/reg/udral/physics/time/TAI64VarTs_0_1.h new file mode 100644 index 0000000..c1af73f --- /dev/null +++ b/hardware/include/reg/udral/physics/time/TAI64VarTs_0_1.h @@ -0,0 +1,279 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64VarTs.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.083309 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.time.TAI64VarTs +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_TIME_TAI64VAR_TS_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_TIME_TAI64VAR_TS_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64VarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64VarTs.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64VarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64VarTs.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64VarTs.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 reg_udral_physics_time_TAI64VarTs_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.time.TAI64VarTs.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_time_TAI64VarTs_0_1_FULL_NAME_ "reg.udral.physics.time.TAI64VarTs" +#define reg_udral_physics_time_TAI64VarTs_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.time.TAI64VarTs.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 reg_udral_physics_time_TAI64VarTs_0_1_EXTENT_BYTES_ 19UL +#define reg_udral_physics_time_TAI64VarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 19UL +static_assert(reg_udral_physics_time_TAI64VarTs_0_1_EXTENT_BYTES_ >= reg_udral_physics_time_TAI64VarTs_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.time.SynchronizedTimestamp.1.0 timestamp + uavcan_time_SynchronizedTimestamp_1_0 timestamp; + + /// reg.udral.physics.time.TAI64Var.0.1 value + reg_udral_physics_time_TAI64Var_0_1 value; +} reg_udral_physics_time_TAI64VarTs_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 reg_udral_physics_time_TAI64VarTs_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 reg_udral_physics_time_TAI64VarTs_0_1_serialize_( + const reg_udral_physics_time_TAI64VarTs_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.physics.time.TAI64Var.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 12UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = reg_udral_physics_time_TAI64Var_0_1_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 96ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_time_TAI64VarTs_0_1_deserialize_( + reg_udral_physics_time_TAI64VarTs_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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + // reg.udral.physics.time.TAI64Var.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = reg_udral_physics_time_TAI64Var_0_1_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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_time_TAI64VarTs_0_1_initialize_(reg_udral_physics_time_TAI64VarTs_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_time_TAI64VarTs_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_TIME_TAI64VAR_TS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/time/TAI64Var_0_1.h b/hardware/include/reg/udral/physics/time/TAI64Var_0_1.h new file mode 100644 index 0000000..b2220fe --- /dev/null +++ b/hardware/include/reg/udral/physics/time/TAI64Var_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64Var.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.080517 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.time.TAI64Var +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_TIME_TAI64VAR_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_TIME_TAI64VAR_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64Var.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64Var.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64Var.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 reg_udral_physics_time_TAI64Var_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.time.TAI64Var.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_time_TAI64Var_0_1_FULL_NAME_ "reg.udral.physics.time.TAI64Var" +#define reg_udral_physics_time_TAI64Var_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.time.TAI64Var.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 reg_udral_physics_time_TAI64Var_0_1_EXTENT_BYTES_ 12UL +#define reg_udral_physics_time_TAI64Var_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(reg_udral_physics_time_TAI64Var_0_1_EXTENT_BYTES_ >= reg_udral_physics_time_TAI64Var_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.physics.time.TAI64.0.1 value + reg_udral_physics_time_TAI64_0_1 value; + + /// saturated float32 error_variance + float error_variance; +} reg_udral_physics_time_TAI64Var_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 reg_udral_physics_time_TAI64Var_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 reg_udral_physics_time_TAI64Var_0_1_serialize_( + const reg_udral_physics_time_TAI64Var_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) < 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; + { // reg.udral.physics.time.TAI64.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 8UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_physics_time_TAI64_0_1_serialize_( + &obj->value, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 64ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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->error_variance); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_time_TAI64Var_0_1_deserialize_( + reg_udral_physics_time_TAI64Var_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; + // reg.udral.physics.time.TAI64.0.1 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err3_ = reg_udral_physics_time_TAI64_0_1_deserialize_( + &out_obj->value, &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 error_variance + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_time_TAI64Var_0_1_initialize_(reg_udral_physics_time_TAI64Var_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_time_TAI64Var_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_TIME_TAI64VAR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/physics/time/TAI64_0_1.h b/hardware/include/reg/udral/physics/time/TAI64_0_1.h new file mode 100644 index 0000000..b3937a2 --- /dev/null +++ b/hardware/include/reg/udral/physics/time/TAI64_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64.0.1.dsdl +// Generated at: 2025-07-17 18:00:17.078062 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.physics.time.TAI64 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_PHYSICS_TIME_TAI64_0_1_INCLUDED_ +#define REG_UDRAL_PHYSICS_TIME_TAI64_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/physics/time/TAI64.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 reg_udral_physics_time_TAI64_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.physics.time.TAI64.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_physics_time_TAI64_0_1_FULL_NAME_ "reg.udral.physics.time.TAI64" +#define reg_udral_physics_time_TAI64_0_1_FULL_NAME_AND_VERSION_ "reg.udral.physics.time.TAI64.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 reg_udral_physics_time_TAI64_0_1_EXTENT_BYTES_ 8UL +#define reg_udral_physics_time_TAI64_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(reg_udral_physics_time_TAI64_0_1_EXTENT_BYTES_ >= reg_udral_physics_time_TAI64_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated int64 tai64n + int64_t tai64n; +} reg_udral_physics_time_TAI64_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 reg_udral_physics_time_TAI64_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 reg_udral_physics_time_TAI64_0_1_serialize_( + const reg_udral_physics_time_TAI64_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) < 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 tai64n + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err0_ = nunavutSetIxx(&buffer[0], capacity_bytes, offset_bits, obj->tai64n, 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_physics_time_TAI64_0_1_deserialize_( + reg_udral_physics_time_TAI64_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 int64 tai64n + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->tai64n = nunavutGetI64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_physics_time_TAI64_0_1_initialize_(reg_udral_physics_time_TAI64_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_physics_time_TAI64_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_PHYSICS_TIME_TAI64_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/service/actuator/common/FaultFlags_0_1.h b/hardware/include/reg/udral/service/actuator/common/FaultFlags_0_1.h new file mode 100644 index 0000000..fb77bda --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/FaultFlags_0_1.h @@ -0,0 +1,446 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/FaultFlags.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.904669 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.FaultFlags +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_FAULT_FLAGS_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_FAULT_FLAGS_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/FaultFlags.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/FaultFlags.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/FaultFlags.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/FaultFlags.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/FaultFlags.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 reg_udral_service_actuator_common_FaultFlags_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.FaultFlags.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_FaultFlags_0_1_FULL_NAME_ "reg.udral.service.actuator.common.FaultFlags" +#define reg_udral_service_actuator_common_FaultFlags_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.FaultFlags.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 reg_udral_service_actuator_common_FaultFlags_0_1_EXTENT_BYTES_ 2UL +#define reg_udral_service_actuator_common_FaultFlags_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(reg_udral_service_actuator_common_FaultFlags_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_FaultFlags_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated bool overload + bool overload; + + /// saturated bool voltage + bool voltage; + + /// saturated bool motor_temperature + bool motor_temperature; + + /// saturated bool controller_temperature + bool controller_temperature; + + /// saturated bool velocity + bool velocity; + + /// saturated bool mechanical + bool mechanical; + + /// saturated bool vibration + bool vibration; + + /// saturated bool configuration + bool configuration; + + /// saturated bool control_mode + bool control_mode; + + /// saturated bool other + bool other; +} reg_udral_service_actuator_common_FaultFlags_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 reg_udral_service_actuator_common_FaultFlags_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 reg_udral_service_actuator_common_FaultFlags_0_1_serialize_( + const reg_udral_service_actuator_common_FaultFlags_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 bool overload + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->overload ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool voltage + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->voltage) + { + 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 motor_temperature + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->motor_temperature) + { + 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 controller_temperature + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->controller_temperature) + { + 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 velocity + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->velocity) + { + 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 mechanical + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->mechanical) + { + 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 vibration + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->vibration) + { + 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 configuration + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->configuration) + { + 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 control_mode + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->control_mode ? 1U : 0U; + offset_bits += 1U; + } + { // void6 + NUNAVUT_ASSERT((offset_bits + 6ULL) <= (capacity_bytes * 8U)); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 6U); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 6UL; + } + { // saturated bool other + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + if (obj->other) + { + 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; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad0_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_FaultFlags_0_1_deserialize_( + reg_udral_service_actuator_common_FaultFlags_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 overload + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + if (offset_bits < capacity_bits) + { + out_obj->overload = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->overload = false; + } + offset_bits += 1U; + // saturated bool voltage + if (offset_bits < capacity_bits) + { + out_obj->voltage = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->voltage = false; + } + offset_bits += 1U; + // saturated bool motor_temperature + if (offset_bits < capacity_bits) + { + out_obj->motor_temperature = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->motor_temperature = false; + } + offset_bits += 1U; + // saturated bool controller_temperature + if (offset_bits < capacity_bits) + { + out_obj->controller_temperature = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->controller_temperature = false; + } + offset_bits += 1U; + // saturated bool velocity + if (offset_bits < capacity_bits) + { + out_obj->velocity = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->velocity = false; + } + offset_bits += 1U; + // saturated bool mechanical + if (offset_bits < capacity_bits) + { + out_obj->mechanical = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->mechanical = false; + } + offset_bits += 1U; + // saturated bool vibration + if (offset_bits < capacity_bits) + { + out_obj->vibration = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->vibration = false; + } + offset_bits += 1U; + // saturated bool configuration + if (offset_bits < capacity_bits) + { + out_obj->configuration = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->configuration = false; + } + offset_bits += 1U; + // saturated bool control_mode + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + if (offset_bits < capacity_bits) + { + out_obj->control_mode = (buffer[offset_bits / 8U] & 1U) != 0U; + } + else + { + out_obj->control_mode = false; + } + offset_bits += 1U; + // void6 + offset_bits += 6; + // saturated bool other + if (offset_bits < capacity_bits) + { + out_obj->other = (buffer[offset_bits / 8U] & (1U << (offset_bits % 8U))) != 0U; + } + else + { + out_obj->other = false; + } + offset_bits += 1U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_FaultFlags_0_1_initialize_(reg_udral_service_actuator_common_FaultFlags_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_FaultFlags_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_FAULT_FLAGS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/service/actuator/common/Feedback_0_1.h b/hardware/include/reg/udral/service/actuator/common/Feedback_0_1.h new file mode 100644 index 0000000..384ec25 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/Feedback_0_1.h @@ -0,0 +1,246 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Feedback.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.909803 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.Feedback +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_FEEDBACK_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_FEEDBACK_0_1_INCLUDED_ + +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Feedback.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Feedback.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Feedback.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Feedback.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Feedback.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 reg_udral_service_actuator_common_Feedback_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.Feedback.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_Feedback_0_1_FULL_NAME_ "reg.udral.service.actuator.common.Feedback" +#define reg_udral_service_actuator_common_Feedback_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.Feedback.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 reg_udral_service_actuator_common_Feedback_0_1_EXTENT_BYTES_ 63UL +#define reg_udral_service_actuator_common_Feedback_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 3UL +static_assert(reg_udral_service_actuator_common_Feedback_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_Feedback_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// reg.udral.service.common.Heartbeat.0.1 heartbeat + reg_udral_service_common_Heartbeat_0_1 heartbeat; + + /// saturated int8 demand_factor_pct + int8_t demand_factor_pct; +} reg_udral_service_actuator_common_Feedback_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 reg_udral_service_actuator_common_Feedback_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 reg_udral_service_actuator_common_Feedback_0_1_serialize_( + const reg_udral_service_actuator_common_Feedback_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) < 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; + { // reg.udral.service.common.Heartbeat.0.1 heartbeat + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_service_common_Heartbeat_0_1_serialize_( + &obj->heartbeat, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated int8 demand_factor_pct + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->demand_factor_pct); // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 24ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_Feedback_0_1_deserialize_( + reg_udral_service_actuator_common_Feedback_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; + // reg.udral.service.common.Heartbeat.0.1 heartbeat + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err2_ = reg_udral_service_common_Heartbeat_0_1_deserialize_( + &out_obj->heartbeat, &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 int8 demand_factor_pct + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->demand_factor_pct = nunavutGetI8(&buffer[0], capacity_bytes, offset_bits, 8); + offset_bits += 8U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_Feedback_0_1_initialize_(reg_udral_service_actuator_common_Feedback_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_Feedback_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_FEEDBACK_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/Status_0_1.h b/hardware/include/reg/udral/service/actuator/common/Status_0_1.h new file mode 100644 index 0000000..ab77569 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/Status_0_1.h @@ -0,0 +1,347 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Status.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.913078 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.Status +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_STATUS_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_STATUS_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Status.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/Status.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 reg_udral_service_actuator_common_Status_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.Status.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_Status_0_1_FULL_NAME_ "reg.udral.service.actuator.common.Status" +#define reg_udral_service_actuator_common_Status_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.Status.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 reg_udral_service_actuator_common_Status_0_1_EXTENT_BYTES_ 63UL +#define reg_udral_service_actuator_common_Status_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 14UL +static_assert(reg_udral_service_actuator_common_Status_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_Status_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// uavcan.si.unit.temperature.Scalar.1.0 motor_temperature + uavcan_si_unit_temperature_Scalar_1_0 motor_temperature; + + /// uavcan.si.unit.temperature.Scalar.1.0 controller_temperature + uavcan_si_unit_temperature_Scalar_1_0 controller_temperature; + + /// saturated uint32 error_count + uint32_t error_count; + + /// reg.udral.service.actuator.common.FaultFlags.0.1 fault_flags + reg_udral_service_actuator_common_FaultFlags_0_1 fault_flags; +} reg_udral_service_actuator_common_Status_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 reg_udral_service_actuator_common_Status_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 reg_udral_service_actuator_common_Status_0_1_serialize_( + const reg_udral_service_actuator_common_Status_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.si.unit.temperature.Scalar.1.0 motor_temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_temperature_Scalar_1_0_serialize_( + &obj->motor_temperature, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.temperature.Scalar.1.0 controller_temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_temperature_Scalar_1_0_serialize_( + &obj->controller_temperature, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint32 error_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->error_count, 32U); + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += 32U; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.service.actuator.common.FaultFlags.0.1 fault_flags + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err5_ = reg_udral_service_actuator_common_FaultFlags_0_1_serialize_( + &obj->fault_flags, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 112ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_Status_0_1_deserialize_( + reg_udral_service_actuator_common_Status_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.si.unit.temperature.Scalar.1.0 motor_temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err7_ = uavcan_si_unit_temperature_Scalar_1_0_deserialize_( + &out_obj->motor_temperature, &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. + // uavcan.si.unit.temperature.Scalar.1.0 controller_temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err8_ = uavcan_si_unit_temperature_Scalar_1_0_deserialize_( + &out_obj->controller_temperature, &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. + } + // saturated uint32 error_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->error_count = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // reg.udral.service.actuator.common.FaultFlags.0.1 fault_flags + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err9_ = reg_udral_service_actuator_common_FaultFlags_0_1_deserialize_( + &out_obj->fault_flags, &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. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_Status_0_1_initialize_(reg_udral_service_actuator_common_Status_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_Status_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_STATUS_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/_0_1.h b/hardware/include/reg/udral/service/actuator/common/_0_1.h new file mode 100644 index 0000000..001758b --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/_0_1.h @@ -0,0 +1,175 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/_.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.917001 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common._ +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON___0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON___0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/_.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/_.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 reg_udral_service_actuator_common___0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common._.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common___0_1_FULL_NAME_ "reg.udral.service.actuator.common._" +#define reg_udral_service_actuator_common___0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common._.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 reg_udral_service_actuator_common___0_1_EXTENT_BYTES_ 0UL +#define reg_udral_service_actuator_common___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(reg_udral_service_actuator_common___0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated float32 CONTROL_TIMEOUT = 1 +#define reg_udral_service_actuator_common___0_1_CONTROL_TIMEOUT (((float) 1.0)) + +/// saturated uint8 MAX_PUBLICATION_PERIOD = 1 +#define reg_udral_service_actuator_common___0_1_MAX_PUBLICATION_PERIOD (1U) + +typedef struct +{ + uint8_t _dummy_; +} reg_udral_service_actuator_common___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 reg_udral_service_actuator_common___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 reg_udral_service_actuator_common___0_1_serialize_( + const reg_udral_service_actuator_common___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 reg_udral_service_actuator_common___0_1_deserialize_( + reg_udral_service_actuator_common___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 reg_udral_service_actuator_common___0_1_initialize_(reg_udral_service_actuator_common___0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common___0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON___0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Scalar_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Scalar_0_1.h new file mode 100644 index 0000000..d907405 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Scalar_0_1.h @@ -0,0 +1,224 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Scalar.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.919020 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Scalar +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_SCALAR_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_SCALAR_0_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Scalar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Scalar.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Scalar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Scalar.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Scalar.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 reg_udral_service_actuator_common_sp_Scalar_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Scalar.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Scalar_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Scalar" +#define reg_udral_service_actuator_common_sp_Scalar_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Scalar.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 reg_udral_service_actuator_common_sp_Scalar_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Scalar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(reg_udral_service_actuator_common_sp_Scalar_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Scalar_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + /// saturated float16 value + float value; +} reg_udral_service_actuator_common_sp_Scalar_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 reg_udral_service_actuator_common_sp_Scalar_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 reg_udral_service_actuator_common_sp_Scalar_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Scalar_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 float16 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Scalar_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Scalar_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 float16 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Scalar_0_1_initialize_(reg_udral_service_actuator_common_sp_Scalar_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Scalar_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_SCALAR_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Vector2_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Vector2_0_1.h new file mode 100644 index 0000000..53f2c89 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Vector2_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector2.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.921556 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Vector2 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR2_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR2_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector2.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector2.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector2.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector2.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector2.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 reg_udral_service_actuator_common_sp_Vector2_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Vector2.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Vector2_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Vector2" +#define reg_udral_service_actuator_common_sp_Vector2_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Vector2.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 reg_udral_service_actuator_common_sp_Vector2_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Vector2_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 4UL +static_assert(reg_udral_service_actuator_common_sp_Vector2_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Vector2_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[2] value +#define reg_udral_service_actuator_common_sp_Vector2_0_1_value_ARRAY_CAPACITY_ 2U +#define reg_udral_service_actuator_common_sp_Vector2_0_1_value_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float16[2] value + float value[2]; +} reg_udral_service_actuator_common_sp_Vector2_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 reg_udral_service_actuator_common_sp_Vector2_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 reg_udral_service_actuator_common_sp_Vector2_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Vector2_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; + { // saturated float16[2] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 2UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->value[_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; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 32ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Vector2_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Vector2_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 float16[2] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 2UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->value[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Vector2_0_1_initialize_(reg_udral_service_actuator_common_sp_Vector2_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Vector2_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR2_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Vector31_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Vector31_0_1.h new file mode 100644 index 0000000..6ce4345 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Vector31_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector31.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.927082 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Vector31 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR31_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR31_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector31.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector31.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector31.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector31.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector31.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 reg_udral_service_actuator_common_sp_Vector31_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Vector31.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Vector31_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Vector31" +#define reg_udral_service_actuator_common_sp_Vector31_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Vector31.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 reg_udral_service_actuator_common_sp_Vector31_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 62UL +static_assert(reg_udral_service_actuator_common_sp_Vector31_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[31] value +#define reg_udral_service_actuator_common_sp_Vector31_0_1_value_ARRAY_CAPACITY_ 31U +#define reg_udral_service_actuator_common_sp_Vector31_0_1_value_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float16[31] value + float value[31]; +} reg_udral_service_actuator_common_sp_Vector31_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 reg_udral_service_actuator_common_sp_Vector31_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 reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Vector31_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) < 496UL) + { + 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[31] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 496ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 31UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->value[_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; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 496ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 496ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Vector31_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Vector31_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 float16[31] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 31UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->value[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Vector31_0_1_initialize_(reg_udral_service_actuator_common_sp_Vector31_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Vector31_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR31_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Vector3_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Vector3_0_1.h new file mode 100644 index 0000000..e2a7668 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Vector3_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector3.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.924326 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Vector3 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR3_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR3_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector3.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector3.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector3.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector3.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector3.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 reg_udral_service_actuator_common_sp_Vector3_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Vector3.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Vector3_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Vector3" +#define reg_udral_service_actuator_common_sp_Vector3_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Vector3.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 reg_udral_service_actuator_common_sp_Vector3_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Vector3_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 6UL +static_assert(reg_udral_service_actuator_common_sp_Vector3_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Vector3_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[3] value +#define reg_udral_service_actuator_common_sp_Vector3_0_1_value_ARRAY_CAPACITY_ 3U +#define reg_udral_service_actuator_common_sp_Vector3_0_1_value_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float16[3] value + float value[3]; +} reg_udral_service_actuator_common_sp_Vector3_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 reg_udral_service_actuator_common_sp_Vector3_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 reg_udral_service_actuator_common_sp_Vector3_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Vector3_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) < 48UL) + { + 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[3] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 48ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->value[_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; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 48ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 48ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Vector3_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Vector3_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 float16[3] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->value[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Vector3_0_1_initialize_(reg_udral_service_actuator_common_sp_Vector3_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Vector3_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR3_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Vector4_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Vector4_0_1.h new file mode 100644 index 0000000..7543051 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Vector4_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector4.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.929847 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Vector4 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR4_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR4_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector4.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector4.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector4.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector4.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector4.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 reg_udral_service_actuator_common_sp_Vector4_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Vector4.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Vector4_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Vector4" +#define reg_udral_service_actuator_common_sp_Vector4_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Vector4.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 reg_udral_service_actuator_common_sp_Vector4_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Vector4_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 8UL +static_assert(reg_udral_service_actuator_common_sp_Vector4_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Vector4_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[4] value +#define reg_udral_service_actuator_common_sp_Vector4_0_1_value_ARRAY_CAPACITY_ 4U +#define reg_udral_service_actuator_common_sp_Vector4_0_1_value_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float16[4] value + float value[4]; +} reg_udral_service_actuator_common_sp_Vector4_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 reg_udral_service_actuator_common_sp_Vector4_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 reg_udral_service_actuator_common_sp_Vector4_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Vector4_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) < 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 float16[4] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 4UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->value[_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; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 64ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Vector4_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Vector4_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 float16[4] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 4UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->value[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Vector4_0_1_initialize_(reg_udral_service_actuator_common_sp_Vector4_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Vector4_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR4_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Vector6_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Vector6_0_1.h new file mode 100644 index 0000000..3f7eed1 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Vector6_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector6.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.932595 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Vector6 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR6_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR6_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector6.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector6.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector6.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector6.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector6.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 reg_udral_service_actuator_common_sp_Vector6_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Vector6.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Vector6_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Vector6" +#define reg_udral_service_actuator_common_sp_Vector6_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Vector6.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 reg_udral_service_actuator_common_sp_Vector6_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Vector6_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(reg_udral_service_actuator_common_sp_Vector6_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Vector6_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[6] value +#define reg_udral_service_actuator_common_sp_Vector6_0_1_value_ARRAY_CAPACITY_ 6U +#define reg_udral_service_actuator_common_sp_Vector6_0_1_value_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float16[6] value + float value[6]; +} reg_udral_service_actuator_common_sp_Vector6_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 reg_udral_service_actuator_common_sp_Vector6_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 reg_udral_service_actuator_common_sp_Vector6_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Vector6_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) < 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 float16[6] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->value[_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; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Vector6_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Vector6_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 float16[6] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->value[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Vector6_0_1_initialize_(reg_udral_service_actuator_common_sp_Vector6_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Vector6_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR6_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/Vector8_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/Vector8_0_1.h new file mode 100644 index 0000000..7b8ff7a --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/Vector8_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector8.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.935352 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp.Vector8 +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR8_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR8_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector8.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector8.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector8.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector8.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/Vector8.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 reg_udral_service_actuator_common_sp_Vector8_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp.Vector8.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp_Vector8_0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp.Vector8" +#define reg_udral_service_actuator_common_sp_Vector8_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp.Vector8.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 reg_udral_service_actuator_common_sp_Vector8_0_1_EXTENT_BYTES_ 512UL +#define reg_udral_service_actuator_common_sp_Vector8_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 16UL +static_assert(reg_udral_service_actuator_common_sp_Vector8_0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp_Vector8_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: saturated float16[8] value +#define reg_udral_service_actuator_common_sp_Vector8_0_1_value_ARRAY_CAPACITY_ 8U +#define reg_udral_service_actuator_common_sp_Vector8_0_1_value_ARRAY_IS_VARIABLE_LENGTH_ false + +typedef struct +{ + /// saturated float16[8] value + float value[8]; +} reg_udral_service_actuator_common_sp_Vector8_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 reg_udral_service_actuator_common_sp_Vector8_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 reg_udral_service_actuator_common_sp_Vector8_0_1_serialize_( + const reg_udral_service_actuator_common_sp_Vector8_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) < 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 float16[8] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 8UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->value[_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; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 128ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_actuator_common_sp_Vector8_0_1_deserialize_( + reg_udral_service_actuator_common_sp_Vector8_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 float16[8] value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 8UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->value[_index1_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_actuator_common_sp_Vector8_0_1_initialize_(reg_udral_service_actuator_common_sp_Vector8_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp_Vector8_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP_VECTOR8_0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/common/sp/_0_1.h b/hardware/include/reg/udral/service/actuator/common/sp/_0_1.h new file mode 100644 index 0000000..9cda938 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/common/sp/_0_1.h @@ -0,0 +1,171 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/_.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.938103 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.common.sp._ +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP___0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP___0_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/_.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/common/sp/_.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 reg_udral_service_actuator_common_sp___0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.common.sp._.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_common_sp___0_1_FULL_NAME_ "reg.udral.service.actuator.common.sp._" +#define reg_udral_service_actuator_common_sp___0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.common.sp._.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 reg_udral_service_actuator_common_sp___0_1_EXTENT_BYTES_ 0UL +#define reg_udral_service_actuator_common_sp___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(reg_udral_service_actuator_common_sp___0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_common_sp___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated float16 EPSILON = 1/2048 +#define reg_udral_service_actuator_common_sp___0_1_EPSILON (((float) (1.0 / 2048.0))) + +typedef struct +{ + uint8_t _dummy_; +} reg_udral_service_actuator_common_sp___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 reg_udral_service_actuator_common_sp___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 reg_udral_service_actuator_common_sp___0_1_serialize_( + const reg_udral_service_actuator_common_sp___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 reg_udral_service_actuator_common_sp___0_1_deserialize_( + reg_udral_service_actuator_common_sp___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 reg_udral_service_actuator_common_sp___0_1_initialize_(reg_udral_service_actuator_common_sp___0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_common_sp___0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_COMMON_SP___0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/esc/_0_1.h b/hardware/include/reg/udral/service/actuator/esc/_0_1.h new file mode 100644 index 0000000..99ede61 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/esc/_0_1.h @@ -0,0 +1,168 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/esc/_.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.941877 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.esc._ +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_ESC___0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_ESC___0_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/esc/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/esc/_.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/esc/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/esc/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/esc/_.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 reg_udral_service_actuator_esc___0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.esc._.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_esc___0_1_FULL_NAME_ "reg.udral.service.actuator.esc._" +#define reg_udral_service_actuator_esc___0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.esc._.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 reg_udral_service_actuator_esc___0_1_EXTENT_BYTES_ 0UL +#define reg_udral_service_actuator_esc___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(reg_udral_service_actuator_esc___0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_esc___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} reg_udral_service_actuator_esc___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 reg_udral_service_actuator_esc___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 reg_udral_service_actuator_esc___0_1_serialize_( + const reg_udral_service_actuator_esc___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 reg_udral_service_actuator_esc___0_1_deserialize_( + reg_udral_service_actuator_esc___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 reg_udral_service_actuator_esc___0_1_initialize_(reg_udral_service_actuator_esc___0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_esc___0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_ESC___0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/actuator/servo/_0_1.h b/hardware/include/reg/udral/service/actuator/servo/_0_1.h new file mode 100644 index 0000000..bd86a21 --- /dev/null +++ b/hardware/include/reg/udral/service/actuator/servo/_0_1.h @@ -0,0 +1,168 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/servo/_.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.940005 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.actuator.servo._ +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_ACTUATOR_SERVO___0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_ACTUATOR_SERVO___0_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/servo/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/servo/_.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/servo/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/servo/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/actuator/servo/_.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 reg_udral_service_actuator_servo___0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.actuator.servo._.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_actuator_servo___0_1_FULL_NAME_ "reg.udral.service.actuator.servo._" +#define reg_udral_service_actuator_servo___0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.actuator.servo._.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 reg_udral_service_actuator_servo___0_1_EXTENT_BYTES_ 0UL +#define reg_udral_service_actuator_servo___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(reg_udral_service_actuator_servo___0_1_EXTENT_BYTES_ >= reg_udral_service_actuator_servo___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} reg_udral_service_actuator_servo___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 reg_udral_service_actuator_servo___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 reg_udral_service_actuator_servo___0_1_serialize_( + const reg_udral_service_actuator_servo___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 reg_udral_service_actuator_servo___0_1_deserialize_( + reg_udral_service_actuator_servo___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 reg_udral_service_actuator_servo___0_1_initialize_(reg_udral_service_actuator_servo___0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_actuator_servo___0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_ACTUATOR_SERVO___0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/battery/Error_0_1.h b/hardware/include/reg/udral/service/battery/Error_0_1.h new file mode 100644 index 0000000..71c139d --- /dev/null +++ b/hardware/include/reg/udral/service/battery/Error_0_1.h @@ -0,0 +1,252 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Error.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.735439 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.battery.Error +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_BATTERY_ERROR_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_BATTERY_ERROR_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/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 reg_udral_service_battery_Error_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.battery.Error.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_battery_Error_0_1_FULL_NAME_ "reg.udral.service.battery.Error" +#define reg_udral_service_battery_Error_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.battery.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 reg_udral_service_battery_Error_0_1_EXTENT_BYTES_ 1UL +#define reg_udral_service_battery_Error_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(reg_udral_service_battery_Error_0_1_EXTENT_BYTES_ >= reg_udral_service_battery_Error_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 NONE = 0 +#define reg_udral_service_battery_Error_0_1_NONE (0U) + +/// saturated uint8 BAD_BATTERY = 10 +#define reg_udral_service_battery_Error_0_1_BAD_BATTERY (10U) + +/// saturated uint8 NEEDS_SERVICE = 11 +#define reg_udral_service_battery_Error_0_1_NEEDS_SERVICE (11U) + +/// saturated uint8 BMS_ERROR = 20 +#define reg_udral_service_battery_Error_0_1_BMS_ERROR (20U) + +/// saturated uint8 CONFIGURATION = 30 +#define reg_udral_service_battery_Error_0_1_CONFIGURATION (30U) + +/// saturated uint8 OVERDISCHARGE = 50 +#define reg_udral_service_battery_Error_0_1_OVERDISCHARGE (50U) + +/// saturated uint8 OVERLOAD = 51 +#define reg_udral_service_battery_Error_0_1_OVERLOAD (51U) + +/// saturated uint8 CELL_OVERVOLTAGE = 60 +#define reg_udral_service_battery_Error_0_1_CELL_OVERVOLTAGE (60U) + +/// saturated uint8 CELL_UNDERVOLTAGE = 61 +#define reg_udral_service_battery_Error_0_1_CELL_UNDERVOLTAGE (61U) + +/// saturated uint8 CELL_COUNT = 62 +#define reg_udral_service_battery_Error_0_1_CELL_COUNT (62U) + +/// saturated uint8 TEMPERATURE_HOT = 100 +#define reg_udral_service_battery_Error_0_1_TEMPERATURE_HOT (100U) + +/// saturated uint8 TEMPERATURE_COLD = 101 +#define reg_udral_service_battery_Error_0_1_TEMPERATURE_COLD (101U) + +typedef struct +{ + /// saturated uint8 value + uint8_t value; +} reg_udral_service_battery_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 reg_udral_service_battery_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 reg_udral_service_battery_Error_0_1_serialize_( + const reg_udral_service_battery_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) < 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_battery_Error_0_1_deserialize_( + reg_udral_service_battery_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; + // saturated uint8 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_battery_Error_0_1_initialize_(reg_udral_service_battery_Error_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_battery_Error_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_BATTERY_ERROR_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/service/battery/Parameters_0_3.h b/hardware/include/reg/udral/service/battery/Parameters_0_3.h new file mode 100644 index 0000000..5006e74 --- /dev/null +++ b/hardware/include/reg/udral/service/battery/Parameters_0_3.h @@ -0,0 +1,928 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Parameters.0.3.dsdl +// Generated at: 2025-07-17 18:00:16.872757 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.battery.Parameters +// Version: 0.3 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_BATTERY_PARAMETERS_0_3_INCLUDED_ +#define REG_UDRAL_SERVICE_BATTERY_PARAMETERS_0_3_INCLUDED_ + +#include +#include +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Parameters.0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Parameters.0.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Parameters.0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Parameters.0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Parameters.0.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 + +/// This type does not have a fixed port-ID. See https://forum.opencyphal.org/t/choosing-message-and-service-ids/889 +#define reg_udral_service_battery_Parameters_0_3_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.battery.Parameters.0.3 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_battery_Parameters_0_3_FULL_NAME_ "reg.udral.service.battery.Parameters" +#define reg_udral_service_battery_Parameters_0_3_FULL_NAME_AND_VERSION_ "reg.udral.service.battery.Parameters.0.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 reg_udral_service_battery_Parameters_0_3_EXTENT_BYTES_ 300UL +#define reg_udral_service_battery_Parameters_0_3_SERIALIZATION_BUFFER_SIZE_BYTES_ 128UL +static_assert(reg_udral_service_battery_Parameters_0_3_EXTENT_BYTES_ >= reg_udral_service_battery_Parameters_0_3_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// Array metadata for: uavcan.si.unit.voltage.Scalar.1.0[2] design_cell_voltage_min_max +#define reg_udral_service_battery_Parameters_0_3_design_cell_voltage_min_max_ARRAY_CAPACITY_ 2U +#define reg_udral_service_battery_Parameters_0_3_design_cell_voltage_min_max_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: saturated uint8[<=64] name +#define reg_udral_service_battery_Parameters_0_3_name_ARRAY_CAPACITY_ 64U +#define reg_udral_service_battery_Parameters_0_3_name_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// truncated uint64 unique_id + uint64_t unique_id; + + /// uavcan.si.unit.mass.Scalar.1.0 mass + uavcan_si_unit_mass_Scalar_1_0 mass; + + /// uavcan.si.unit.electric_charge.Scalar.1.0 design_capacity + uavcan_si_unit_electric_charge_Scalar_1_0 design_capacity; + + /// uavcan.si.unit.voltage.Scalar.1.0[2] design_cell_voltage_min_max + uavcan_si_unit_voltage_Scalar_1_0 design_cell_voltage_min_max[2]; + + /// uavcan.si.unit.electric_current.Scalar.1.0 discharge_current + uavcan_si_unit_electric_current_Scalar_1_0 discharge_current; + + /// uavcan.si.unit.electric_current.Scalar.1.0 discharge_current_burst + uavcan_si_unit_electric_current_Scalar_1_0 discharge_current_burst; + + /// uavcan.si.unit.electric_current.Scalar.1.0 charge_current + uavcan_si_unit_electric_current_Scalar_1_0 charge_current; + + /// uavcan.si.unit.electric_current.Scalar.1.0 charge_current_fast + uavcan_si_unit_electric_current_Scalar_1_0 charge_current_fast; + + /// uavcan.si.unit.electric_current.Scalar.1.0 charge_termination_threshold + uavcan_si_unit_electric_current_Scalar_1_0 charge_termination_threshold; + + /// uavcan.si.unit.voltage.Scalar.1.0 charge_voltage + uavcan_si_unit_voltage_Scalar_1_0 charge_voltage; + + /// saturated uint16 cycle_count + uint16_t cycle_count; + + /// saturated uint8 series_cell_count + uint8_t series_cell_count; + + /// saturated uint7 state_of_health_pct + uint8_t state_of_health_pct; + + /// reg.udral.service.battery.Technology.0.1 technology + reg_udral_service_battery_Technology_0_1 technology; + + /// uavcan.si.unit.voltage.Scalar.1.0 nominal_voltage + uavcan_si_unit_voltage_Scalar_1_0 nominal_voltage; + + /// truncated uint40 unix_manufacture_time + uint64_t unix_manufacture_time; + + /// saturated uint8[<=64] name + struct /// Array address equivalence guarantee: &elements[0] == &name + { + uint8_t elements[reg_udral_service_battery_Parameters_0_3_name_ARRAY_CAPACITY_]; + size_t count; + } name; +} reg_udral_service_battery_Parameters_0_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 reg_udral_service_battery_Parameters_0_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 reg_udral_service_battery_Parameters_0_3_serialize_( + const reg_udral_service_battery_Parameters_0_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) < 1024UL) + { + 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 uint64 unique_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->unique_id, 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.mass.Scalar.1.0 mass + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_mass_Scalar_1_0_serialize_( + &obj->mass, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_charge.Scalar.1.0 design_capacity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_electric_charge_Scalar_1_0_serialize_( + &obj->design_capacity, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.voltage.Scalar.1.0[2] design_cell_voltage_min_max + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 2UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err6_ = uavcan_si_unit_voltage_Scalar_1_0_serialize_( + &obj->design_cell_voltage_min_max[_index0_], &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 64ULL); + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_current.Scalar.1.0 discharge_current + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes3_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_bytes); + int8_t _err8_ = uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + &obj->discharge_current, &buffer[offset_bits / 8U], &_size_bytes3_); + 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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) == 32ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad4_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad4_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad4_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad4_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_current.Scalar.1.0 discharge_current_burst + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes4_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes4_) <= capacity_bytes); + int8_t _err10_ = uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + &obj->discharge_current_burst, &buffer[offset_bits / 8U], &_size_bytes4_); + 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. + NUNAVUT_ASSERT((_size_bytes4_ * 8U) == 32ULL); + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad5_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad5_ > 0); + const int8_t _err11_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad5_); // Optimize? + if (_err11_ < 0) + { + return _err11_; + } + offset_bits += _pad5_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_current.Scalar.1.0 charge_current + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes5_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes5_) <= capacity_bytes); + int8_t _err12_ = uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + &obj->charge_current, &buffer[offset_bits / 8U], &_size_bytes5_); + 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. + NUNAVUT_ASSERT((_size_bytes5_ * 8U) == 32ULL); + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad6_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad6_ > 0); + const int8_t _err13_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad6_); // Optimize? + if (_err13_ < 0) + { + return _err13_; + } + offset_bits += _pad6_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_current.Scalar.1.0 charge_current_fast + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes6_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes6_) <= capacity_bytes); + int8_t _err14_ = uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + &obj->charge_current_fast, &buffer[offset_bits / 8U], &_size_bytes6_); + 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. + NUNAVUT_ASSERT((_size_bytes6_ * 8U) == 32ULL); + offset_bits += _size_bytes6_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad7_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad7_ > 0); + const int8_t _err15_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad7_); // Optimize? + if (_err15_ < 0) + { + return _err15_; + } + offset_bits += _pad7_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_current.Scalar.1.0 charge_termination_threshold + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes7_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes7_) <= capacity_bytes); + int8_t _err16_ = uavcan_si_unit_electric_current_Scalar_1_0_serialize_( + &obj->charge_termination_threshold, &buffer[offset_bits / 8U], &_size_bytes7_); + if (_err16_ < 0) + { + return _err16_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((_size_bytes7_ * 8U) == 32ULL); + offset_bits += _size_bytes7_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad8_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad8_ > 0); + const int8_t _err17_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad8_); // Optimize? + if (_err17_ < 0) + { + return _err17_; + } + offset_bits += _pad8_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.voltage.Scalar.1.0 charge_voltage + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes8_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes8_) <= capacity_bytes); + int8_t _err18_ = uavcan_si_unit_voltage_Scalar_1_0_serialize_( + &obj->charge_voltage, &buffer[offset_bits / 8U], &_size_bytes8_); + if (_err18_ < 0) + { + return _err18_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((_size_bytes8_ * 8U) == 32ULL); + offset_bits += _size_bytes8_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint16 cycle_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err19_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->cycle_count, 16U); + if (_err19_ < 0) + { + return _err19_; + } + offset_bits += 16U; + } + { // void8 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = 0U; + offset_bits += 8UL; + } + { // saturated uint8 series_cell_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // Saturation code not emitted -- native representation matches the serialized representation. + buffer[offset_bits / 8U] = (uint8_t)(obj->series_cell_count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + } + { // saturated uint7 state_of_health_pct + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 7ULL) <= (capacity_bytes * 8U)); + uint8_t _sat0_ = obj->state_of_health_pct; + if (_sat0_ > 127U) + { + _sat0_ = 127U; + } + buffer[offset_bits / 8U] = (uint8_t)(_sat0_); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 7U; + } + { // void1 + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + const int8_t _err20_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, 1U); // Optimize? + if (_err20_ < 0) + { + return _err20_; + } + offset_bits += 1UL; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad9_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad9_ > 0); + const int8_t _err21_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad9_); // Optimize? + if (_err21_ < 0) + { + return _err21_; + } + offset_bits += _pad9_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.service.battery.Technology.0.1 technology + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes9_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes9_) <= capacity_bytes); + int8_t _err22_ = reg_udral_service_battery_Technology_0_1_serialize_( + &obj->technology, &buffer[offset_bits / 8U], &_size_bytes9_); + if (_err22_ < 0) + { + return _err22_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((_size_bytes9_ * 8U) == 8ULL); + offset_bits += _size_bytes9_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad10_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad10_ > 0); + const int8_t _err23_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad10_); // Optimize? + if (_err23_ < 0) + { + return _err23_; + } + offset_bits += _pad10_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.voltage.Scalar.1.0 nominal_voltage + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes10_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes10_) <= capacity_bytes); + int8_t _err24_ = uavcan_si_unit_voltage_Scalar_1_0_serialize_( + &obj->nominal_voltage, &buffer[offset_bits / 8U], &_size_bytes10_); + if (_err24_ < 0) + { + return _err24_; + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((_size_bytes10_ * 8U) == 32ULL); + offset_bits += _size_bytes10_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // truncated uint40 unix_manufacture_time + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + const int8_t _err25_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->unix_manufacture_time, 40U); + if (_err25_ < 0) + { + return _err25_; + } + offset_bits += 40U; + } + { // saturated uint8[<=64] name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 520ULL) <= (capacity_bytes * 8U)); + if (obj->name.count > 64) + { + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < obj->name.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad11_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad11_ > 0); + const int8_t _err26_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad11_); // Optimize? + if (_err26_ < 0) + { + return _err26_; + } + offset_bits += _pad11_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 512ULL); + NUNAVUT_ASSERT(offset_bits <= 1024ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_battery_Parameters_0_3_deserialize_( + reg_udral_service_battery_Parameters_0_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; + // truncated uint64 unique_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->unique_id = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.mass.Scalar.1.0 mass + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes11_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err27_ = uavcan_si_unit_mass_Scalar_1_0_deserialize_( + &out_obj->mass, &buffer[offset_bits / 8U], &_size_bytes11_); + if (_err27_ < 0) + { + return _err27_; + } + offset_bits += _size_bytes11_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.electric_charge.Scalar.1.0 design_capacity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes12_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err28_ = uavcan_si_unit_electric_charge_Scalar_1_0_deserialize_( + &out_obj->design_capacity, &buffer[offset_bits / 8U], &_size_bytes12_); + if (_err28_ < 0) + { + return _err28_; + } + offset_bits += _size_bytes12_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.voltage.Scalar.1.0[2] design_cell_voltage_min_max + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < 2UL; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes13_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err29_ = uavcan_si_unit_voltage_Scalar_1_0_deserialize_( + &out_obj->design_cell_voltage_min_max[_index2_], &buffer[offset_bits / 8U], &_size_bytes13_); + if (_err29_ < 0) + { + return _err29_; + } + offset_bits += _size_bytes13_ * 8U; // Advance by the size of the nested serialized representation. + } + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.electric_current.Scalar.1.0 discharge_current + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes14_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err30_ = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + &out_obj->discharge_current, &buffer[offset_bits / 8U], &_size_bytes14_); + if (_err30_ < 0) + { + return _err30_; + } + offset_bits += _size_bytes14_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.electric_current.Scalar.1.0 discharge_current_burst + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes15_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err31_ = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + &out_obj->discharge_current_burst, &buffer[offset_bits / 8U], &_size_bytes15_); + if (_err31_ < 0) + { + return _err31_; + } + offset_bits += _size_bytes15_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.electric_current.Scalar.1.0 charge_current + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes16_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err32_ = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + &out_obj->charge_current, &buffer[offset_bits / 8U], &_size_bytes16_); + if (_err32_ < 0) + { + return _err32_; + } + offset_bits += _size_bytes16_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.electric_current.Scalar.1.0 charge_current_fast + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes17_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err33_ = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + &out_obj->charge_current_fast, &buffer[offset_bits / 8U], &_size_bytes17_); + if (_err33_ < 0) + { + return _err33_; + } + offset_bits += _size_bytes17_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.electric_current.Scalar.1.0 charge_termination_threshold + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes18_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err34_ = uavcan_si_unit_electric_current_Scalar_1_0_deserialize_( + &out_obj->charge_termination_threshold, &buffer[offset_bits / 8U], &_size_bytes18_); + if (_err34_ < 0) + { + return _err34_; + } + offset_bits += _size_bytes18_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.voltage.Scalar.1.0 charge_voltage + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes19_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err35_ = uavcan_si_unit_voltage_Scalar_1_0_deserialize_( + &out_obj->charge_voltage, &buffer[offset_bits / 8U], &_size_bytes19_); + if (_err35_ < 0) + { + return _err35_; + } + offset_bits += _size_bytes19_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint16 cycle_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->cycle_count = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // void8 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 8; + // saturated uint8 series_cell_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->series_cell_count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->series_cell_count = 0U; + } + offset_bits += 8U; + // saturated uint7 state_of_health_pct + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + if ((offset_bits + 7U) <= capacity_bits) + { + out_obj->state_of_health_pct = buffer[offset_bits / 8U] & 127U; + } + else + { + out_obj->state_of_health_pct = 0U; + } + offset_bits += 7U; + // void1 + offset_bits += 1; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // reg.udral.service.battery.Technology.0.1 technology + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes20_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err36_ = reg_udral_service_battery_Technology_0_1_deserialize_( + &out_obj->technology, &buffer[offset_bits / 8U], &_size_bytes20_); + if (_err36_ < 0) + { + return _err36_; + } + offset_bits += _size_bytes20_ * 8U; // Advance by the size of the nested serialized representation. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.voltage.Scalar.1.0 nominal_voltage + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes21_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err37_ = uavcan_si_unit_voltage_Scalar_1_0_deserialize_( + &out_obj->nominal_voltage, &buffer[offset_bits / 8U], &_size_bytes21_); + if (_err37_ < 0) + { + return _err37_; + } + offset_bits += _size_bytes21_ * 8U; // Advance by the size of the nested serialized representation. + } + // truncated uint40 unix_manufacture_time + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->unix_manufacture_time = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // saturated uint8[<=64] name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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 > 64U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < out_obj->name.count; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->name.elements[_index3_] = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->name.elements[_index3_] = 0U; + } + offset_bits += 8U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_battery_Parameters_0_3_initialize_(reg_udral_service_battery_Parameters_0_3* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_battery_Parameters_0_3_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_BATTERY_PARAMETERS_0_3_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/battery/Status_0_2.h b/hardware/include/reg/udral/service/battery/Status_0_2.h new file mode 100644 index 0000000..0d7be91 --- /dev/null +++ b/hardware/include/reg/udral/service/battery/Status_0_2.h @@ -0,0 +1,471 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Status.0.2.dsdl +// Generated at: 2025-07-17 18:00:16.884313 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.battery.Status +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_BATTERY_STATUS_0_2_INCLUDED_ +#define REG_UDRAL_SERVICE_BATTERY_STATUS_0_2_INCLUDED_ + +#include +#include +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Status.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Status.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 reg_udral_service_battery_Status_0_2_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.battery.Status.0.2 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_battery_Status_0_2_FULL_NAME_ "reg.udral.service.battery.Status" +#define reg_udral_service_battery_Status_0_2_FULL_NAME_AND_VERSION_ "reg.udral.service.battery.Status.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 reg_udral_service_battery_Status_0_2_EXTENT_BYTES_ 600UL +#define reg_udral_service_battery_Status_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_ 526UL +static_assert(reg_udral_service_battery_Status_0_2_EXTENT_BYTES_ >= reg_udral_service_battery_Status_0_2_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_CELLS = 255 +#define reg_udral_service_battery_Status_0_2_MAX_CELLS (255U) + +/// Array metadata for: uavcan.si.unit.temperature.Scalar.1.0[2] temperature_min_max +#define reg_udral_service_battery_Status_0_2_temperature_min_max_ARRAY_CAPACITY_ 2U +#define reg_udral_service_battery_Status_0_2_temperature_min_max_ARRAY_IS_VARIABLE_LENGTH_ false + +/// Array metadata for: saturated float16[<=255] cell_voltages +#define reg_udral_service_battery_Status_0_2_cell_voltages_ARRAY_CAPACITY_ 255U +#define reg_udral_service_battery_Status_0_2_cell_voltages_ARRAY_IS_VARIABLE_LENGTH_ true + +typedef struct +{ + /// reg.udral.service.common.Heartbeat.0.1 heartbeat + reg_udral_service_common_Heartbeat_0_1 heartbeat; + + /// uavcan.si.unit.temperature.Scalar.1.0[2] temperature_min_max + uavcan_si_unit_temperature_Scalar_1_0 temperature_min_max[2]; + + /// uavcan.si.unit.electric_charge.Scalar.1.0 available_charge + uavcan_si_unit_electric_charge_Scalar_1_0 available_charge; + + /// reg.udral.service.battery.Error.0.1 error + reg_udral_service_battery_Error_0_1 _error; + + /// saturated float16[<=255] cell_voltages + struct /// Array address equivalence guarantee: &elements[0] == &cell_voltages + { + float elements[reg_udral_service_battery_Status_0_2_cell_voltages_ARRAY_CAPACITY_]; + size_t count; + } cell_voltages; +} reg_udral_service_battery_Status_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 reg_udral_service_battery_Status_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 reg_udral_service_battery_Status_0_2_serialize_( + const reg_udral_service_battery_Status_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) < 4208UL) + { + 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; + { // reg.udral.service.common.Heartbeat.0.1 heartbeat + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_service_common_Heartbeat_0_1_serialize_( + &obj->heartbeat, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.temperature.Scalar.1.0[2] temperature_min_max + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 2UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_si_unit_temperature_Scalar_1_0_serialize_( + &obj->temperature_min_max[_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 64ULL); + (void) _origin0_; + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad1_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.electric_charge.Scalar.1.0 available_charge + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + int8_t _err4_ = uavcan_si_unit_electric_charge_Scalar_1_0_serialize_( + &obj->available_charge, &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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 32ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // reg.udral.service.battery.Error.0.1 error + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes3_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_bytes); + int8_t _err6_ = reg_udral_service_battery_Error_0_1_serialize_( + &obj->_error, &buffer[offset_bits / 8U], &_size_bytes3_); + 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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) == 8ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float16[<=255] cell_voltages + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 4088ULL) <= (capacity_bytes * 8U)); + if (obj->cell_voltages.count > 255) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + // Array length prefix: truncated uint8 + buffer[offset_bits / 8U] = (uint8_t)(obj->cell_voltages.count); // C std, 6.3.1.3 Signed and unsigned integers + offset_bits += 8U; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < obj->cell_voltages.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + float _sat0_ = obj->cell_voltages.elements[_index1_]; + if (isfinite(_sat0_)) + { + if (_sat0_ < ((float) -65504.0)) + { + _sat0_ = ((float) -65504.0); + } + if (_sat0_ > ((float) 65504.0)) + { + _sat0_ = ((float) 65504.0); + } + } + const int8_t _err7_ = nunavutSetF16(&buffer[0], capacity_bytes, offset_bits, _sat0_); + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += 16U; + } + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 128ULL); + NUNAVUT_ASSERT(offset_bits <= 4208ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_battery_Status_0_2_deserialize_( + reg_udral_service_battery_Status_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; + // reg.udral.service.common.Heartbeat.0.1 heartbeat + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err9_ = reg_udral_service_common_Heartbeat_0_1_deserialize_( + &out_obj->heartbeat, &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.si.unit.temperature.Scalar.1.0[2] temperature_min_max + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < 2UL; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err10_ = uavcan_si_unit_temperature_Scalar_1_0_deserialize_( + &out_obj->temperature_min_max[_index2_], &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. + // uavcan.si.unit.electric_charge.Scalar.1.0 available_charge + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err11_ = uavcan_si_unit_electric_charge_Scalar_1_0_deserialize_( + &out_obj->available_charge, &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. + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // reg.udral.service.battery.Error.0.1 error + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err12_ = reg_udral_service_battery_Error_0_1_deserialize_( + &out_obj->_error, &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. + } + // saturated float16[<=255] cell_voltages + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // Array length prefix: truncated uint8 + if ((offset_bits + 8U) <= capacity_bits) + { + out_obj->cell_voltages.count = buffer[offset_bits / 8U] & 255U; + } + else + { + out_obj->cell_voltages.count = 0U; + } + offset_bits += 8U; + if (out_obj->cell_voltages.count > 255U) + { + return -NUNAVUT_ERROR_REPRESENTATION_BAD_ARRAY_LENGTH; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < out_obj->cell_voltages.count; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->cell_voltages.elements[_index3_] = nunavutGetF16(&buffer[0], capacity_bytes, offset_bits); + offset_bits += 16U; + } + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_battery_Status_0_2_initialize_(reg_udral_service_battery_Status_0_2* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_battery_Status_0_2_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_BATTERY_STATUS_0_2_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/battery/Technology_0_1.h b/hardware/include/reg/udral/service/battery/Technology_0_1.h new file mode 100644 index 0000000..681c8d4 --- /dev/null +++ b/hardware/include/reg/udral/service/battery/Technology_0_1.h @@ -0,0 +1,288 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Technology.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.890056 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.battery.Technology +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_BATTERY_TECHNOLOGY_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_BATTERY_TECHNOLOGY_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Technology.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Technology.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Technology.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Technology.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/Technology.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 reg_udral_service_battery_Technology_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.battery.Technology.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_battery_Technology_0_1_FULL_NAME_ "reg.udral.service.battery.Technology" +#define reg_udral_service_battery_Technology_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.battery.Technology.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 reg_udral_service_battery_Technology_0_1_EXTENT_BYTES_ 1UL +#define reg_udral_service_battery_Technology_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(reg_udral_service_battery_Technology_0_1_EXTENT_BYTES_ >= reg_udral_service_battery_Technology_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 OTHER = 0 +#define reg_udral_service_battery_Technology_0_1_OTHER (0U) + +/// saturated uint8 LI_SOCL2 = 10 +#define reg_udral_service_battery_Technology_0_1_LI_SOCL2 (10U) + +/// saturated uint8 LI_BCX = 11 +#define reg_udral_service_battery_Technology_0_1_LI_BCX (11U) + +/// saturated uint8 LI_MNO2 = 12 +#define reg_udral_service_battery_Technology_0_1_LI_MNO2 (12U) + +/// saturated uint8 ZN_O2 = 20 +#define reg_udral_service_battery_Technology_0_1_ZN_O2 (20U) + +/// saturated uint8 AL_O2 = 21 +#define reg_udral_service_battery_Technology_0_1_AL_O2 (21U) + +/// saturated uint8 ZN_MNO2_NH4CL = 30 +#define reg_udral_service_battery_Technology_0_1_ZN_MNO2_NH4CL (30U) + +/// saturated uint8 ZN_MNO2_ZNCL2 = 31 +#define reg_udral_service_battery_Technology_0_1_ZN_MNO2_ZNCL2 (31U) + +/// saturated uint8 ZN_MNO2_KOH = 32 +#define reg_udral_service_battery_Technology_0_1_ZN_MNO2_KOH (32U) + +/// saturated uint8 LI_LCO = 100 +#define reg_udral_service_battery_Technology_0_1_LI_LCO (100U) + +/// saturated uint8 LI_LFP = 101 +#define reg_udral_service_battery_Technology_0_1_LI_LFP (101U) + +/// saturated uint8 LI_NMC = 102 +#define reg_udral_service_battery_Technology_0_1_LI_NMC (102U) + +/// saturated uint8 LI_NCA = 103 +#define reg_udral_service_battery_Technology_0_1_LI_NCA (103U) + +/// saturated uint8 LI_LMO = 104 +#define reg_udral_service_battery_Technology_0_1_LI_LMO (104U) + +/// saturated uint8 LI_S = 105 +#define reg_udral_service_battery_Technology_0_1_LI_S (105U) + +/// saturated uint8 LI_LCO_POUCH = 110 +#define reg_udral_service_battery_Technology_0_1_LI_LCO_POUCH (110U) + +/// saturated uint8 LI_LFP_POUCH = 111 +#define reg_udral_service_battery_Technology_0_1_LI_LFP_POUCH (111U) + +/// saturated uint8 NI_MH = 120 +#define reg_udral_service_battery_Technology_0_1_NI_MH (120U) + +/// saturated uint8 NI_CD = 121 +#define reg_udral_service_battery_Technology_0_1_NI_CD (121U) + +/// saturated uint8 NI_ZN = 122 +#define reg_udral_service_battery_Technology_0_1_NI_ZN (122U) + +/// saturated uint8 NI_FE = 123 +#define reg_udral_service_battery_Technology_0_1_NI_FE (123U) + +/// saturated uint8 PB_AC = 130 +#define reg_udral_service_battery_Technology_0_1_PB_AC (130U) + +/// saturated uint8 PB_AC_SEALED = 131 +#define reg_udral_service_battery_Technology_0_1_PB_AC_SEALED (131U) + +/// saturated uint8 EDLC = 200 +#define reg_udral_service_battery_Technology_0_1_EDLC (200U) + +typedef struct +{ + /// saturated uint8 value + uint8_t value; +} reg_udral_service_battery_Technology_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 reg_udral_service_battery_Technology_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 reg_udral_service_battery_Technology_0_1_serialize_( + const reg_udral_service_battery_Technology_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; + { // saturated uint8 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_battery_Technology_0_1_deserialize_( + reg_udral_service_battery_Technology_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 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_battery_Technology_0_1_initialize_(reg_udral_service_battery_Technology_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_battery_Technology_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_BATTERY_TECHNOLOGY_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/service/battery/_0_1.h b/hardware/include/reg/udral/service/battery/_0_1.h new file mode 100644 index 0000000..2dd09d2 --- /dev/null +++ b/hardware/include/reg/udral/service/battery/_0_1.h @@ -0,0 +1,168 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/_.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.892997 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.battery._ +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_BATTERY___0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_BATTERY___0_1_INCLUDED_ + +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/_.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/_.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/battery/_.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 reg_udral_service_battery___0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.battery._.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_battery___0_1_FULL_NAME_ "reg.udral.service.battery._" +#define reg_udral_service_battery___0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.battery._.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 reg_udral_service_battery___0_1_EXTENT_BYTES_ 0UL +#define reg_udral_service_battery___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 0UL +static_assert(reg_udral_service_battery___0_1_EXTENT_BYTES_ >= reg_udral_service_battery___0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +typedef struct +{ + uint8_t _dummy_; +} reg_udral_service_battery___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 reg_udral_service_battery___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 reg_udral_service_battery___0_1_serialize_( + const reg_udral_service_battery___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 reg_udral_service_battery___0_1_deserialize_( + reg_udral_service_battery___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 reg_udral_service_battery___0_1_initialize_(reg_udral_service_battery___0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_battery___0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_BATTERY___0_1_INCLUDED_ + diff --git a/hardware/include/reg/udral/service/common/Heartbeat_0_1.h b/hardware/include/reg/udral/service/common/Heartbeat_0_1.h new file mode 100644 index 0000000..731dd82 --- /dev/null +++ b/hardware/include/reg/udral/service/common/Heartbeat_0_1.h @@ -0,0 +1,283 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Heartbeat.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.898666 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.common.Heartbeat +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_COMMON_HEARTBEAT_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_COMMON_HEARTBEAT_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Heartbeat.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Heartbeat.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Heartbeat.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Heartbeat.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Heartbeat.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 reg_udral_service_common_Heartbeat_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.common.Heartbeat.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_common_Heartbeat_0_1_FULL_NAME_ "reg.udral.service.common.Heartbeat" +#define reg_udral_service_common_Heartbeat_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.common.Heartbeat.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 reg_udral_service_common_Heartbeat_0_1_EXTENT_BYTES_ 2UL +#define reg_udral_service_common_Heartbeat_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 2UL +static_assert(reg_udral_service_common_Heartbeat_0_1_EXTENT_BYTES_ >= reg_udral_service_common_Heartbeat_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_PUBLICATION_PERIOD = 1 +#define reg_udral_service_common_Heartbeat_0_1_MAX_PUBLICATION_PERIOD (1U) + +typedef struct +{ + /// reg.udral.service.common.Readiness.0.1 readiness + reg_udral_service_common_Readiness_0_1 readiness; + + /// uavcan.node.Health.1.0 health + uavcan_node_Health_1_0 health; +} reg_udral_service_common_Heartbeat_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 reg_udral_service_common_Heartbeat_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 reg_udral_service_common_Heartbeat_0_1_serialize_( + const reg_udral_service_common_Heartbeat_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; + { // reg.udral.service.common.Readiness.0.1 readiness + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = reg_udral_service_common_Readiness_0_1_serialize_( + &obj->readiness, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 8ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.Health.1.0 health + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err2_ = uavcan_node_Health_1_0_serialize_( + &obj->health, &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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 8ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_common_Heartbeat_0_1_deserialize_( + reg_udral_service_common_Heartbeat_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; + // reg.udral.service.common.Readiness.0.1 readiness + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err4_ = reg_udral_service_common_Readiness_0_1_deserialize_( + &out_obj->readiness, &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.Health.1.0 health + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_node_Health_1_0_deserialize_( + &out_obj->health, &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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_common_Heartbeat_0_1_initialize_(reg_udral_service_common_Heartbeat_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_common_Heartbeat_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_COMMON_HEARTBEAT_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/service/common/Readiness_0_1.h b/hardware/include/reg/udral/service/common/Readiness_0_1.h new file mode 100644 index 0000000..166c41f --- /dev/null +++ b/hardware/include/reg/udral/service/common/Readiness_0_1.h @@ -0,0 +1,224 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Readiness.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.902160 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.common.Readiness +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_COMMON_READINESS_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_COMMON_READINESS_0_1_INCLUDED_ + +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Readiness.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Readiness.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Readiness.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Readiness.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/common/Readiness.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 reg_udral_service_common_Readiness_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.common.Readiness.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_common_Readiness_0_1_FULL_NAME_ "reg.udral.service.common.Readiness" +#define reg_udral_service_common_Readiness_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.common.Readiness.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 reg_udral_service_common_Readiness_0_1_EXTENT_BYTES_ 1UL +#define reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 1UL +static_assert(reg_udral_service_common_Readiness_0_1_EXTENT_BYTES_ >= reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint2 SLEEP = 0 +#define reg_udral_service_common_Readiness_0_1_SLEEP (0U) + +/// saturated uint2 STANDBY = 2 +#define reg_udral_service_common_Readiness_0_1_STANDBY (2U) + +/// saturated uint2 ENGAGED = 3 +#define reg_udral_service_common_Readiness_0_1_ENGAGED (3U) + +typedef struct +{ + /// truncated uint2 value + uint8_t value; +} reg_udral_service_common_Readiness_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 reg_udral_service_common_Readiness_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 reg_udral_service_common_Readiness_0_1_serialize_( + const reg_udral_service_common_Readiness_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 uint2 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = (uint8_t)(obj->value); // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_common_Readiness_0_1_deserialize_( + reg_udral_service_common_Readiness_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 uint2 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_common_Readiness_0_1_initialize_(reg_udral_service_common_Readiness_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_common_Readiness_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_COMMON_READINESS_0_1_INCLUDED_ diff --git a/hardware/include/reg/udral/service/sensor/Status_0_1.h b/hardware/include/reg/udral/service/sensor/Status_0_1.h new file mode 100644 index 0000000..e056c8e --- /dev/null +++ b/hardware/include/reg/udral/service/sensor/Status_0_1.h @@ -0,0 +1,302 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/sensor/Status.0.1.dsdl +// Generated at: 2025-07-17 18:00:16.894935 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: reg.udral.service.sensor.Status +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// enable_override_variable_array_capacity: False +// cast_format: (({type}) {value}) + +#ifndef REG_UDRAL_SERVICE_SENSOR_STATUS_0_1_INCLUDED_ +#define REG_UDRAL_SERVICE_SENSOR_STATUS_0_1_INCLUDED_ + +#include +#include +#include +#include +#include + +static_assert( NUNAVUT_SUPPORT_LANGUAGE_OPTION_TARGET_ENDIANNESS == 1693710260, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/sensor/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/sensor/Status.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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/sensor/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/sensor/Status.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/reg/udral/service/sensor/Status.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 reg_udral_service_sensor_Status_0_1_HAS_FIXED_PORT_ID_ false + +// +-------------------------------------------------------------------------------------------------------------------+ +// | reg.udral.service.sensor.Status.0.1 +// +-------------------------------------------------------------------------------------------------------------------+ +#define reg_udral_service_sensor_Status_0_1_FULL_NAME_ "reg.udral.service.sensor.Status" +#define reg_udral_service_sensor_Status_0_1_FULL_NAME_AND_VERSION_ "reg.udral.service.sensor.Status.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 reg_udral_service_sensor_Status_0_1_EXTENT_BYTES_ 63UL +#define reg_udral_service_sensor_Status_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_ 12UL +static_assert(reg_udral_service_sensor_Status_0_1_EXTENT_BYTES_ >= reg_udral_service_sensor_Status_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_, + "Internal constraint violation"); + +/// saturated uint8 MAX_PUBLICATION_PERIOD = 1 +#define reg_udral_service_sensor_Status_0_1_MAX_PUBLICATION_PERIOD (1U) + +typedef struct +{ + /// uavcan.si.unit.duration.Scalar.1.0 data_validity_period + uavcan_si_unit_duration_Scalar_1_0 data_validity_period; + + /// saturated uint32 error_count + uint32_t error_count; + + /// uavcan.si.unit.temperature.Scalar.1.0 sensor_temperature + uavcan_si_unit_temperature_Scalar_1_0 sensor_temperature; +} reg_udral_service_sensor_Status_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 reg_udral_service_sensor_Status_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 reg_udral_service_sensor_Status_0_1_serialize_( + const reg_udral_service_sensor_Status_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) < 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; + { // uavcan.si.unit.duration.Scalar.1.0 data_validity_period + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + int8_t _err0_ = uavcan_si_unit_duration_Scalar_1_0_serialize_( + &obj->data_validity_period, &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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint32 error_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // Saturation code not emitted -- native representation matches the serialized representation. + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->error_count, 32U); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.si.unit.temperature.Scalar.1.0 sensor_temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + int8_t _err3_ = uavcan_si_unit_temperature_Scalar_1_0_serialize_( + &obj->sensor_temperature, &buffer[offset_bits / 8U], &_size_bytes1_); + 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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 reg_udral_service_sensor_Status_0_1_deserialize_( + reg_udral_service_sensor_Status_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.si.unit.duration.Scalar.1.0 data_validity_period + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err5_ = uavcan_si_unit_duration_Scalar_1_0_deserialize_( + &out_obj->data_validity_period, &buffer[offset_bits / 8U], &_size_bytes2_); + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested serialized representation. + } + // saturated uint32 error_count + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->error_count = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.si.unit.temperature.Scalar.1.0 sensor_temperature + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + const int8_t _err6_ = uavcan_si_unit_temperature_Scalar_1_0_deserialize_( + &out_obj->sensor_temperature, &buffer[offset_bits / 8U], &_size_bytes3_); + if (_err6_ < 0) + { + return _err6_; + } + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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 reg_udral_service_sensor_Status_0_1_initialize_(reg_udral_service_sensor_Status_0_1* const out_obj) +{ + if (out_obj != NULL) + { + size_t size_bytes = 0; + const uint8_t buf = 0; + const int8_t err = reg_udral_service_sensor_Status_0_1_deserialize_(out_obj, &buf, &size_bytes); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // REG_UDRAL_SERVICE_SENSOR_STATUS_0_1_INCLUDED_ + diff --git a/hardware/include/uavcan/_register/Access_1_0.h b/hardware/include/uavcan/_register/Access_1_0.h new file mode 100644 index 0000000..db23d52 --- /dev/null +++ b/hardware/include/uavcan/_register/Access_1_0.h @@ -0,0 +1,558 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/register/384.Access.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.048490 UTC +// Is deprecated: no +// Fixed port-ID: 384 +// Full name: uavcan.register.Access +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.register.Value.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2072ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 259UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 2072ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 4120ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes4_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes4_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes4_ * 8U) == 56ULL); + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated bool mutable + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->_mutable ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool persistent + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 6ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.register.Value.1.0 value + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2072ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes5_ = 259UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes5_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes5_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes5_ * 8U) <= 2072ULL); + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err10_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err10_ < 0) + { + return _err10_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 72ULL); + NUNAVUT_ASSERT(offset_bits <= 2136ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_ACCESS_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/_register/List_1_0.h b/hardware/include/uavcan/_register/List_1_0.h new file mode 100644 index 0000000..d18b79c --- /dev/null +++ b/hardware/include/uavcan/_register/List_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/register/385.List.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.054324 UTC +// Is deprecated: no +// Fixed port-ID: 385 +// Full name: uavcan.register.List +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2048ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_LIST_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/_register/Name_1_0.h b/hardware/include/uavcan/_register/Name_1_0.h new file mode 100644 index 0000000..31398f1 --- /dev/null +++ b/hardware/include/uavcan/_register/Name_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/register/Name.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.058104 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.register.Name +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->name.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2048ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->name.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_REGISTER_NAME_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/_register/Value_1_0.h b/hardware/include/uavcan/_register/Value_1_0.h new file mode 100644 index 0000000..e04c4ac --- /dev/null +++ b/hardware/include/uavcan/_register/Value_1_0.h @@ -0,0 +1,1049 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/register/Value.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.060804 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.register.Value +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 0ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 0UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 0ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (1U == obj->_tag_) // uavcan.primitive.String.1.0 string + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 2064ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (2U == obj->_tag_) // uavcan.primitive.Unstructured.1.0 unstructured + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes2_ * 8U) <= 2064ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (3U == obj->_tag_) // uavcan.primitive.array.Bit.1.0 bit + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes3_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes3_ * 8U) <= 2064ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (4U == obj->_tag_) // uavcan.primitive.array.Integer64.1.0 integer64 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes4_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes4_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes4_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes4_ * 8U) <= 2056ULL); + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (5U == obj->_tag_) // uavcan.primitive.array.Integer32.1.0 integer32 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes5_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes5_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes5_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes5_ * 8U) <= 2056ULL); + offset_bits += _size_bytes5_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (6U == obj->_tag_) // uavcan.primitive.array.Integer16.1.0 integer16 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes6_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes6_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes6_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes6_ * 8U) <= 2056ULL); + offset_bits += _size_bytes6_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (7U == obj->_tag_) // uavcan.primitive.array.Integer8.1.0 integer8 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes7_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes7_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes7_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes7_ * 8U) <= 2064ULL); + offset_bits += _size_bytes7_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (8U == obj->_tag_) // uavcan.primitive.array.Natural64.1.0 natural64 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes8_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes8_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes8_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes8_ * 8U) <= 2056ULL); + offset_bits += _size_bytes8_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (9U == obj->_tag_) // uavcan.primitive.array.Natural32.1.0 natural32 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes9_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes9_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes9_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes9_ * 8U) <= 2056ULL); + offset_bits += _size_bytes9_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (10U == obj->_tag_) // uavcan.primitive.array.Natural16.1.0 natural16 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes10_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes10_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes10_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes10_ * 8U) <= 2056ULL); + offset_bits += _size_bytes10_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (11U == obj->_tag_) // uavcan.primitive.array.Natural8.1.0 natural8 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes11_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes11_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes11_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes11_ * 8U) <= 2064ULL); + offset_bits += _size_bytes11_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (12U == obj->_tag_) // uavcan.primitive.array.Real64.1.0 real64 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes12_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes12_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes12_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes12_ * 8U) <= 2056ULL); + offset_bits += _size_bytes12_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (13U == obj->_tag_) // uavcan.primitive.array.Real32.1.0 real32 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes13_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes13_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes13_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes13_ * 8U) <= 2056ULL); + offset_bits += _size_bytes13_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (14U == obj->_tag_) // uavcan.primitive.array.Real16.1.0 real16 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes14_ = 257UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes14_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes14_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes14_ * 8U) <= 2056ULL); + offset_bits += _size_bytes14_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err15_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err15_ < 0) + { + return _err15_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2072ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes15_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes16_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes17_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes18_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes19_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes20_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes21_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes22_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes23_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes24_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes25_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes26_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes27_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes28_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes29_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/diagnostic/Record_1_0.h b/hardware/include/uavcan/diagnostic/Record_1_0.h new file mode 100644 index 0000000..a038d7a --- /dev/null +++ b/hardware/include/uavcan/diagnostic/Record_1_0.h @@ -0,0 +1,352 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/diagnostic/8184.Record.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.237001 UTC +// Is deprecated: yes +// Fixed port-ID: 8184 +// Full name: uavcan.diagnostic.Record +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.diagnostic.Severity.1.0 severity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 8ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=112] text + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->text.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 72ULL); + NUNAVUT_ASSERT(offset_bits <= 968ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->text.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_DIAGNOSTIC_RECORD_1_0_INCLUDED_ + diff --git a/hardware/include/uavcan/diagnostic/Record_1_1.h b/hardware/include/uavcan/diagnostic/Record_1_1.h new file mode 100644 index 0000000..f038eec --- /dev/null +++ b/hardware/include/uavcan/diagnostic/Record_1_1.h @@ -0,0 +1,343 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/diagnostic/8184.Record.1.1.dsdl +// Generated at: 2025-07-17 18:00:19.233079 UTC +// Is deprecated: no +// Fixed port-ID: 8184 +// Full name: uavcan.diagnostic.Record +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.diagnostic.Severity.1.0 severity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 8ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=255] text + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->text.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 72ULL); + NUNAVUT_ASSERT(offset_bits <= 2112ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->text.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_DIAGNOSTIC_RECORD_1_1_INCLUDED_ + diff --git a/hardware/include/uavcan/diagnostic/Severity_1_0.h b/hardware/include/uavcan/diagnostic/Severity_1_0.h new file mode 100644 index 0000000..0ca86ce --- /dev/null +++ b/hardware/include/uavcan/diagnostic/Severity_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/diagnostic/Severity.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.240722 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.diagnostic.Severity +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 3ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_DIAGNOSTIC_SEVERITY_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/Error_1_0.h b/hardware/include/uavcan/file/Error_1_0.h new file mode 100644 index 0000000..891a568 --- /dev/null +++ b/hardware/include/uavcan/file/Error_1_0.h @@ -0,0 +1,243 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/Error.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.620559 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.file.Error +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_ERROR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/GetInfo_0_1.h b/hardware/include/uavcan/file/GetInfo_0_1.h new file mode 100644 index 0000000..a3a7d83 --- /dev/null +++ b/hardware/include/uavcan/file/GetInfo_0_1.h @@ -0,0 +1,552 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/405.GetInfo.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.713722 UTC +// Is deprecated: yes +// Fixed port-ID: 405 +// Full name: uavcan.file.GetInfo +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 904ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 904ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // truncated uint40 size + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->is_file_not_directory ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool is_link + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 4ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 104ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->size = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 unix_timestamp_of_last_modification + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->unix_timestamp_of_last_modification = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // saturated bool is_file_not_directory + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_GET_INFO_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/file/GetInfo_0_2.h b/hardware/include/uavcan/file/GetInfo_0_2.h new file mode 100644 index 0000000..89f07a3 --- /dev/null +++ b/hardware/include/uavcan/file/GetInfo_0_2.h @@ -0,0 +1,543 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/405.GetInfo.0.2.dsdl +// Generated at: 2025-07-17 18:00:18.709632 UTC +// Is deprecated: no +// Fixed port-ID: 405 +// Full name: uavcan.file.GetInfo +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2048ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // truncated uint40 size + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->is_file_not_directory ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool is_link + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 4ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 104ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->size = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 unix_timestamp_of_last_modification + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->unix_timestamp_of_last_modification = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // saturated bool is_file_not_directory + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_GET_INFO_0_2_INCLUDED_ diff --git a/hardware/include/uavcan/file/List_0_1.h b/hardware/include/uavcan/file/List_0_1.h new file mode 100644 index 0000000..15f3294 --- /dev/null +++ b/hardware/include/uavcan/file/List_0_1.h @@ -0,0 +1,474 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/406.List.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.719979 UTC +// Is deprecated: yes +// Fixed port-ID: 406 +// Full name: uavcan.file.List +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.1.0 directory_path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 904ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 72ULL); + NUNAVUT_ASSERT(offset_bits <= 968ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->entry_index = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // void32 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 directory_path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + (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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.1.0 entry_base_name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes2_ * 8U) <= 904ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 40ULL); + NUNAVUT_ASSERT(offset_bits <= 936ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.1.0 entry_base_name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_LIST_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/file/List_0_2.h b/hardware/include/uavcan/file/List_0_2.h new file mode 100644 index 0000000..6c37b52 --- /dev/null +++ b/hardware/include/uavcan/file/List_0_2.h @@ -0,0 +1,465 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/406.List.0.2.dsdl +// Generated at: 2025-07-17 18:00:18.717040 UTC +// Is deprecated: no +// Fixed port-ID: 406 +// Full name: uavcan.file.List +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.2.0 directory_path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 72ULL); + NUNAVUT_ASSERT(offset_bits <= 2112ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->entry_index = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // void32 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 directory_path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + (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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.2.0 entry_base_name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes2_ * 8U) <= 2048ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 40ULL); + NUNAVUT_ASSERT(offset_bits <= 2080ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.file.Path.2.0 entry_base_name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_LIST_0_2_INCLUDED_ diff --git a/hardware/include/uavcan/file/Modify_1_0.h b/hardware/include/uavcan/file/Modify_1_0.h new file mode 100644 index 0000000..bbd2806 --- /dev/null +++ b/hardware/include/uavcan/file/Modify_1_0.h @@ -0,0 +1,529 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/407.Modify.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.726153 UTC +// Is deprecated: yes +// Fixed port-ID: 407 +// Full name: uavcan.file.Modify +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->preserve_source ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool overwrite_destination + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 30ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.1.0 source + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 904ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.1.0 destination + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 904ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 48ULL); + NUNAVUT_ASSERT(offset_bits <= 1840ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes4_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes4_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes4_ * 8U) == 16ULL); + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_MODIFY_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/Modify_1_1.h b/hardware/include/uavcan/file/Modify_1_1.h new file mode 100644 index 0000000..056586d --- /dev/null +++ b/hardware/include/uavcan/file/Modify_1_1.h @@ -0,0 +1,520 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/407.Modify.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.722941 UTC +// Is deprecated: no +// Fixed port-ID: 407 +// Full name: uavcan.file.Modify +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->preserve_source ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool overwrite_destination + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 30ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.2.0 source + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.2.0 destination + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 2048ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 48ULL); + NUNAVUT_ASSERT(offset_bits <= 4128ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes4_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes4_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes4_ * 8U) == 16ULL); + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_MODIFY_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/file/Path_1_0.h b/hardware/include/uavcan/file/Path_1_0.h new file mode 100644 index 0000000..347586a --- /dev/null +++ b/hardware/include/uavcan/file/Path_1_0.h @@ -0,0 +1,272 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/Path.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.731042 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.file.Path +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->path.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 904ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->path.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_PATH_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/Path_2_0.h b/hardware/include/uavcan/file/Path_2_0.h new file mode 100644 index 0000000..321a21e --- /dev/null +++ b/hardware/include/uavcan/file/Path_2_0.h @@ -0,0 +1,263 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/Path.2.0.dsdl +// Generated at: 2025-07-17 18:00:18.729163 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.file.Path +// Version: 2.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->path.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2048ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->path.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_PATH_2_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/Read_1_0.h b/hardware/include/uavcan/file/Read_1_0.h new file mode 100644 index 0000000..2036696 --- /dev/null +++ b/hardware/include/uavcan/file/Read_1_0.h @@ -0,0 +1,500 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/408.Read.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.735588 UTC +// Is deprecated: yes +// Fixed port-ID: 408 +// Full name: uavcan.file.Read +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.1.0 path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 904ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 48ULL); + NUNAVUT_ASSERT(offset_bits <= 944ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=256] data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 32ULL); + NUNAVUT_ASSERT(offset_bits <= 2080ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_READ_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/Read_1_1.h b/hardware/include/uavcan/file/Read_1_1.h new file mode 100644 index 0000000..9c909bf --- /dev/null +++ b/hardware/include/uavcan/file/Read_1_1.h @@ -0,0 +1,483 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/408.Read.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.732751 UTC +// Is deprecated: no +// Fixed port-ID: 408 +// Full name: uavcan.file.Read +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.2.0 path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 48ULL); + NUNAVUT_ASSERT(offset_bits <= 2088ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.primitive.Unstructured.1.0 data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes3_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes3_ * 8U) <= 2064ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err8_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err8_ < 0) + { + return _err8_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 32ULL); + NUNAVUT_ASSERT(offset_bits <= 2080ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_READ_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/file/Write_1_0.h b/hardware/include/uavcan/file/Write_1_0.h new file mode 100644 index 0000000..b15cd15 --- /dev/null +++ b/hardware/include/uavcan/file/Write_1_0.h @@ -0,0 +1,502 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/409.Write.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.741326 UTC +// Is deprecated: yes +// Fixed port-ID: 409 +// Full name: uavcan.file.Write +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.1.0 path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 113UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 904ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=192] data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1544ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 56ULL); + NUNAVUT_ASSERT(offset_bits <= 2488ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_WRITE_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/file/Write_1_1.h b/hardware/include/uavcan/file/Write_1_1.h new file mode 100644 index 0000000..4a896b9 --- /dev/null +++ b/hardware/include/uavcan/file/Write_1_1.h @@ -0,0 +1,482 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/file/409.Write.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.738573 UTC +// Is deprecated: no +// Fixed port-ID: 409 +// Full name: uavcan.file.Write +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.file.Path.2.0 path + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 256UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 2048ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.primitive.Unstructured.1.0 data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 258UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 16ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 2064ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 64ULL); + NUNAVUT_ASSERT(offset_bits <= 4152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes4_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes4_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes4_ * 8U) == 16ULL); + offset_bits += _size_bytes4_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_FILE_WRITE_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_1.h b/hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_1.h new file mode 100644 index 0000000..049eb38 --- /dev/null +++ b/hardware/include/uavcan/internet/udp/HandleIncomingPacket_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/internet/udp/500.HandleIncomingPacket.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.220020 UTC +// Is deprecated: yes +// Fixed port-ID: 500 +// Full name: uavcan.internet.udp.HandleIncomingPacket +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2488ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->payload.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 32ULL); + NUNAVUT_ASSERT(offset_bits <= 2504ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=309] payload + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->payload.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_2.h b/hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_2.h new file mode 100644 index 0000000..4e726bd --- /dev/null +++ b/hardware/include/uavcan/internet/udp/HandleIncomingPacket_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/internet/udp/500.HandleIncomingPacket.0.2.dsdl +// Generated at: 2025-07-17 18:00:19.216163 UTC +// Is deprecated: no +// Fixed port-ID: 500 +// Full name: uavcan.internet.udp.HandleIncomingPacket +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 4080ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->payload.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 32ULL); + NUNAVUT_ASSERT(offset_bits <= 4096ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=508] payload + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->payload.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_HANDLE_INCOMING_PACKET_0_2_INCLUDED_ diff --git a/hardware/include/uavcan/internet/udp/OutgoingPacket_0_1.h b/hardware/include/uavcan/internet/udp/OutgoingPacket_0_1.h new file mode 100644 index 0000000..4fa61b5 --- /dev/null +++ b/hardware/include/uavcan/internet/udp/OutgoingPacket_0_1.h @@ -0,0 +1,421 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/internet/udp/8174.OutgoingPacket.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.228491 UTC +// Is deprecated: yes +// Fixed port-ID: 8174 +// Full name: uavcan.internet.udp.OutgoingPacket +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 368ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->destination_address.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->use_masquerading ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool use_dtls + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 6ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2096ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < obj->payload.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 64ULL); + NUNAVUT_ASSERT(offset_bits <= 2504ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint16 destination_port + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->destination_port = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=45] destination_address + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < out_obj->destination_address.count; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < out_obj->payload.count; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_1_INCLUDED_ + diff --git a/hardware/include/uavcan/internet/udp/OutgoingPacket_0_2.h b/hardware/include/uavcan/internet/udp/OutgoingPacket_0_2.h new file mode 100644 index 0000000..091bd82 --- /dev/null +++ b/hardware/include/uavcan/internet/udp/OutgoingPacket_0_2.h @@ -0,0 +1,412 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/internet/udp/8174.OutgoingPacket.0.2.dsdl +// Generated at: 2025-07-17 18:00:19.223762 UTC +// Is deprecated: no +// Fixed port-ID: 8174 +// Full name: uavcan.internet.udp.OutgoingPacket +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 368ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->destination_address.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + buffer[offset_bits / 8U] = obj->use_masquerading ? 1U : 0U; + offset_bits += 1U; + } + { // saturated bool use_dtls + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 6ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 4080ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < obj->payload.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 64ULL); + NUNAVUT_ASSERT(offset_bits <= 4488ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->session_id = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint16 destination_port + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->destination_port = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=45] destination_address + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < out_obj->destination_address.count; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < out_obj->payload.count; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_INTERNET_UDP_OUTGOING_PACKET_0_2_INCLUDED_ + diff --git a/hardware/include/uavcan/metatransport/can/ArbitrationID_0_1.h b/hardware/include/uavcan/metatransport/can/ArbitrationID_0_1.h new file mode 100644 index 0000000..124d5e1 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/ArbitrationID_0_1.h @@ -0,0 +1,332 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/ArbitrationID.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.977305 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.ArbitrationID +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (1U == obj->_tag_) // uavcan.metatransport.can.ExtendedArbitrationID.0.1 extended + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 32ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 40ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/metatransport/can/BaseArbitrationID_0_1.h b/hardware/include/uavcan/metatransport/can/BaseArbitrationID_0_1.h new file mode 100644 index 0000000..68223d5 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/BaseArbitrationID_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/BaseArbitrationID.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.980957 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.BaseArbitrationID +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 11ULL) <= (capacity_bytes * 8U)); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 11U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 11U; + } + { // void21 + NUNAVUT_ASSERT((offset_bits + 21ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_BASE_ARBITRATION_ID_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/can/DataClassic_0_1.h b/hardware/include/uavcan/metatransport/can/DataClassic_0_1.h new file mode 100644 index 0000000..0cc725e --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/DataClassic_0_1.h @@ -0,0 +1,293 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/DataClassic.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.983508 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.DataClassic +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 5UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 40ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=8] data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 72ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 48ULL); + NUNAVUT_ASSERT(offset_bits <= 112ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_DATA_CLASSIC_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/can/DataFD_0_1.h b/hardware/include/uavcan/metatransport/can/DataFD_0_1.h new file mode 100644 index 0000000..1850464 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/DataFD_0_1.h @@ -0,0 +1,293 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/DataFD.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.986876 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.DataFD +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 5UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 40ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=64] data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 520ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 48ULL); + NUNAVUT_ASSERT(offset_bits <= 560ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_DATA_FD_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/can/Error_0_1.h b/hardware/include/uavcan/metatransport/can/Error_0_1.h new file mode 100644 index 0000000..de7d805 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/Error_0_1.h @@ -0,0 +1,205 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/Error.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.990235 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Error +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 32; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_ERROR_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/can/ExtendedArbitrationID_0_1.h b/hardware/include/uavcan/metatransport/can/ExtendedArbitrationID_0_1.h new file mode 100644 index 0000000..6a98464 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/ExtendedArbitrationID_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/ExtendedArbitrationID.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.992556 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.ExtendedArbitrationID +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 29ULL) <= (capacity_bytes * 8U)); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, obj->value, 29U); + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += 29U; + } + { // void3 + NUNAVUT_ASSERT((offset_bits + 3ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_EXTENDED_ARBITRATION_ID_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/can/Frame_0_1.h b/hardware/include/uavcan/metatransport/can/Frame_0_1.h new file mode 100644 index 0000000..4a5232d --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/Frame_0_1.h @@ -0,0 +1,290 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/Frame.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.999591 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Frame +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.metatransport.can.Manifestation.0.1 manifestation + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 568ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 71UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 40ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 568ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 96ULL); + NUNAVUT_ASSERT(offset_bits <= 624ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_FRAME_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/can/Frame_0_2.h b/hardware/include/uavcan/metatransport/can/Frame_0_2.h new file mode 100644 index 0000000..5b9f383 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/Frame_0_2.h @@ -0,0 +1,443 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/Frame.0.2.dsdl +// Generated at: 2025-07-17 18:00:18.995157 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Frame +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (1U == obj->_tag_) // uavcan.metatransport.can.DataFD.0.1 data_fd + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 560ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 70UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 48ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 560ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (2U == obj->_tag_) // uavcan.metatransport.can.DataClassic.0.1 data_classic + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 112ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 14UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) >= 48ULL); + NUNAVUT_ASSERT((_size_bytes2_ * 8U) <= 112ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (3U == obj->_tag_) // uavcan.metatransport.can.RTR.0.1 remote_transmission_request + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes3_ = 5UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) == 40ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 40ULL); + NUNAVUT_ASSERT(offset_bits <= 568ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/metatransport/can/Manifestation_0_1.h b/hardware/include/uavcan/metatransport/can/Manifestation_0_1.h new file mode 100644 index 0000000..4b2f5c4 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/Manifestation_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/Manifestation.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.002913 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.Manifestation +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 4UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 32ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (1U == obj->_tag_) // uavcan.metatransport.can.DataFD.0.1 data_fd + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 560ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 70UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 48ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 560ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (2U == obj->_tag_) // uavcan.metatransport.can.DataClassic.0.1 data_classic + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 112ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 14UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) >= 48ULL); + NUNAVUT_ASSERT((_size_bytes2_ * 8U) <= 112ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (3U == obj->_tag_) // uavcan.metatransport.can.RTR.0.1 remote_transmission_request + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes3_ = 5UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) == 40ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 40ULL); + NUNAVUT_ASSERT(offset_bits <= 568ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes6_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes7_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/metatransport/can/RTR_0_1.h b/hardware/include/uavcan/metatransport/can/RTR_0_1.h new file mode 100644 index 0000000..3175387 --- /dev/null +++ b/hardware/include/uavcan/metatransport/can/RTR_0_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/can/RTR.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.007074 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.can.RTR +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 5UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 40ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 40ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_CAN_RTR_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/ethernet/EtherType_0_1.h b/hardware/include/uavcan/metatransport/ethernet/EtherType_0_1.h new file mode 100644 index 0000000..221c700 --- /dev/null +++ b/hardware/include/uavcan/metatransport/ethernet/EtherType_0_1.h @@ -0,0 +1,222 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/ethernet/EtherType.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.018181 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.ethernet.EtherType +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_ETHERNET_ETHER_TYPE_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/ethernet/Frame_0_1.h b/hardware/include/uavcan/metatransport/ethernet/Frame_0_1.h new file mode 100644 index 0000000..db60745 --- /dev/null +++ b/hardware/include/uavcan/metatransport/ethernet/Frame_0_1.h @@ -0,0 +1,380 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/ethernet/Frame.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.020674 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.ethernet.Frame +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 48ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 6UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 48ULL); + (void) _origin0_; + } + { // saturated uint8[6] source + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 48ULL) <= (capacity_bytes * 8U)); + const size_t _origin1_ = offset_bits; + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin1_) == 48ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.metatransport.ethernet.EtherType.0.1 ethertype + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=9216] payload + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 73744ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < obj->payload.count; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 128ULL); + NUNAVUT_ASSERT(offset_bits <= 73856ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < 6UL; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index4_ = 0U; _index4_ < 6UL; ++_index4_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index5_ = 0U; _index5_ < out_obj->payload.count; ++_index5_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_ETHERNET_FRAME_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/serial/Fragment_0_1.h b/hardware/include/uavcan/metatransport/serial/Fragment_0_1.h new file mode 100644 index 0000000..d295851 --- /dev/null +++ b/hardware/include/uavcan/metatransport/serial/Fragment_0_1.h @@ -0,0 +1,302 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/serial/Fragment.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.973125 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.serial.Fragment +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=256] data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 72ULL); + NUNAVUT_ASSERT(offset_bits <= 2120ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/serial/Fragment_0_2.h b/hardware/include/uavcan/metatransport/serial/Fragment_0_2.h new file mode 100644 index 0000000..3c92ef2 --- /dev/null +++ b/hardware/include/uavcan/metatransport/serial/Fragment_0_2.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/serial/Fragment.0.2.dsdl +// Generated at: 2025-07-17 18:00:18.970126 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.metatransport.serial.Fragment +// Version: 0.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16400ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 16400ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_SERIAL_FRAGMENT_0_2_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/udp/Endpoint_0_1.h b/hardware/include/uavcan/metatransport/udp/Endpoint_0_1.h new file mode 100644 index 0000000..6928717 --- /dev/null +++ b/hardware/include/uavcan/metatransport/udp/Endpoint_0_1.h @@ -0,0 +1,308 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/udp/Endpoint.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.009591 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.udp.Endpoint +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (void) _origin0_; + } + { // saturated uint8[6] mac_address + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 48ULL) <= (capacity_bytes * 8U)); + const size_t _origin1_ = offset_bits; + for (size_t _index1_ = 0U; _index1_ < 6UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin1_) == 48ULL); + (void) _origin1_; + } + { // saturated uint16 port + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 256ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < 16UL; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < 6UL; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->port = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // void64 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 64; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_UDP_ENDPOINT_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/metatransport/udp/Frame_0_1.h b/hardware/include/uavcan/metatransport/udp/Frame_0_1.h new file mode 100644 index 0000000..d532d41 --- /dev/null +++ b/hardware/include/uavcan/metatransport/udp/Frame_0_1.h @@ -0,0 +1,409 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/metatransport/udp/Frame.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.013741 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.metatransport.udp.Frame +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // void8 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.metatransport.udp.Endpoint.0.1 source + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 256ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 32UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 256ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.metatransport.udp.Endpoint.0.1 destination + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 256ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 32UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 256ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[<=9188] data + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 73520ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->data.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 592ULL); + NUNAVUT_ASSERT(offset_bits <= 74096ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + offset_bits += 8; + offset_bits = (offset_bits + 7U) & ~(size_t) 7U; // Align on 8 bits. + // uavcan.metatransport.udp.Endpoint.0.1 source + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->data.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_METATRANSPORT_UDP_FRAME_0_1_INCLUDED_ + diff --git a/hardware/include/uavcan/node/ExecuteCommand_1_0.h b/hardware/include/uavcan/node/ExecuteCommand_1_0.h new file mode 100644 index 0000000..8f404ee --- /dev/null +++ b/hardware/include/uavcan/node/ExecuteCommand_1_0.h @@ -0,0 +1,477 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/435.ExecuteCommand.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.084689 UTC +// Is deprecated: yes +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 904ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 24ULL); + NUNAVUT_ASSERT(offset_bits <= 920ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=112] parameter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/ExecuteCommand_1_1.h b/hardware/include/uavcan/node/ExecuteCommand_1_1.h new file mode 100644 index 0000000..897bf51 --- /dev/null +++ b/hardware/include/uavcan/node/ExecuteCommand_1_1.h @@ -0,0 +1,477 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/435.ExecuteCommand.1.1.dsdl +// Generated at: 2025-07-17 18:00:19.080228 UTC +// Is deprecated: yes +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 24ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=255] parameter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/node/ExecuteCommand_1_2.h b/hardware/include/uavcan/node/ExecuteCommand_1_2.h new file mode 100644 index 0000000..3befb8f --- /dev/null +++ b/hardware/include/uavcan/node/ExecuteCommand_1_2.h @@ -0,0 +1,480 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/435.ExecuteCommand.1.2.dsdl +// Generated at: 2025-07-17 18:00:19.075692 UTC +// Is deprecated: yes +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.2 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 24ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=255] parameter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_2_INCLUDED_ diff --git a/hardware/include/uavcan/node/ExecuteCommand_1_3.h b/hardware/include/uavcan/node/ExecuteCommand_1_3.h new file mode 100644 index 0000000..4769725 --- /dev/null +++ b/hardware/include/uavcan/node/ExecuteCommand_1_3.h @@ -0,0 +1,533 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/435.ExecuteCommand.1.3.dsdl +// Generated at: 2025-07-17 18:00:19.070333 UTC +// Is deprecated: no +// Fixed port-ID: 435 +// Full name: uavcan.node.ExecuteCommand +// Version: 1.3 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2048ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->parameter.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 24ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->command = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint8[<=255] parameter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->parameter.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 376ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < obj->output.count; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 384ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < out_obj->output.count; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_EXECUTE_COMMAND_1_3_INCLUDED_ diff --git a/hardware/include/uavcan/node/GetInfo_1_0.h b/hardware/include/uavcan/node/GetInfo_1_0.h new file mode 100644 index 0000000..298b148 --- /dev/null +++ b/hardware/include/uavcan/node/GetInfo_1_0.h @@ -0,0 +1,671 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/430.GetInfo.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.089089 UTC +// Is deprecated: no +// Fixed port-ID: 430 +// Full name: uavcan.node.GetInfo +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.Version.1.0 hardware_version + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 16ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.Version.1.0 software_version + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes2_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 16ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint64 software_vcs_revision_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (void) _origin0_; + } + { // saturated uint8[<=50] name + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 408ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < obj->name.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 72ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index2_ = 0U; _index2_ < obj->software_image_crc.count; ++_index2_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1784ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index3_ = 0U; _index3_ < obj->certificate_of_authenticity.count; ++_index3_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err7_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err7_ < 0) + { + return _err7_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 264ULL); + NUNAVUT_ASSERT(offset_bits <= 2504ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes4_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes5_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->software_vcs_revision_id = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + // saturated uint8[16] unique_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index4_ = 0U; _index4_ < 16UL; ++_index4_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index5_ = 0U; _index5_ < out_obj->name.count; ++_index5_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index6_ = 0U; _index6_ < out_obj->software_image_crc.count; ++_index6_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->software_image_crc.elements[_index6_] = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 64); + offset_bits += 64U; + } + // saturated uint8[<=222] certificate_of_authenticity + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index7_ = 0U; _index7_ < out_obj->certificate_of_authenticity.count; ++_index7_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_GET_INFO_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/GetTransportStatistics_0_1.h b/hardware/include/uavcan/node/GetTransportStatistics_0_1.h new file mode 100644 index 0000000..b30904a --- /dev/null +++ b/hardware/include/uavcan/node/GetTransportStatistics_0_1.h @@ -0,0 +1,431 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/434.GetTransportStatistics.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.096086 UTC +// Is deprecated: no +// Fixed port-ID: 434 +// Full name: uavcan.node.GetTransportStatistics +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 120ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 15UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 120ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.IOStatistics.0.1[<=3] network_interface_statistics + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 368ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->network_interface_statistics.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 120ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 15UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 120ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 128ULL); + NUNAVUT_ASSERT(offset_bits <= 488ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->network_interface_statistics.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_GET_TRANSPORT_STATISTICS_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/node/Health_1_0.h b/hardware/include/uavcan/node/Health_1_0.h new file mode 100644 index 0000000..1848fc5 --- /dev/null +++ b/hardware/include/uavcan/node/Health_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/Health.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.100479 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.Health +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_HEALTH_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/Heartbeat_1_0.h b/hardware/include/uavcan/node/Heartbeat_1_0.h new file mode 100644 index 0000000..b41b1e4 --- /dev/null +++ b/hardware/include/uavcan/node/Heartbeat_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/7509.Heartbeat.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.103041 UTC +// Is deprecated: no +// Fixed port-ID: 7509 +// Full name: uavcan.node.Heartbeat +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.Health.1.0 health + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 8ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.Mode.1.0 mode + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 8ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8 vendor_specific_status_code + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 56ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_HEARTBEAT_1_0_INCLUDED_ + diff --git a/hardware/include/uavcan/node/ID_1_0.h b/hardware/include/uavcan/node/ID_1_0.h new file mode 100644 index 0000000..430a628 --- /dev/null +++ b/hardware/include/uavcan/node/ID_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/ID.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.106937 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.ID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_ID_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/IOStatistics_0_1.h b/hardware/include/uavcan/node/IOStatistics_0_1.h new file mode 100644 index 0000000..9c6acbe --- /dev/null +++ b/hardware/include/uavcan/node/IOStatistics_0_1.h @@ -0,0 +1,246 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/IOStatistics.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.109269 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.IOStatistics +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 40ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 120ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->num_emitted = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 num_received + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->num_received = nunavutGetU64(&buffer[0], capacity_bytes, offset_bits, 40); + offset_bits += 40U; + // truncated uint40 num_errored + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_IO_STATISTICS_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/node/Mode_1_0.h b/hardware/include/uavcan/node/Mode_1_0.h new file mode 100644 index 0000000..1e043fe --- /dev/null +++ b/hardware/include/uavcan/node/Mode_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/Mode.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.112216 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.Mode +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 3ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_MODE_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/Version_1_0.h b/hardware/include/uavcan/node/Version_1_0.h new file mode 100644 index 0000000..5cc2032 --- /dev/null +++ b/hardware/include/uavcan/node/Version_1_0.h @@ -0,0 +1,237 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/Version.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.114602 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.Version +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_VERSION_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/port/ID_1_0.h b/hardware/include/uavcan/node/port/ID_1_0.h new file mode 100644 index 0000000..bd58dcf --- /dev/null +++ b/hardware/include/uavcan/node/port/ID_1_0.h @@ -0,0 +1,332 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/ID.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.117243 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.ID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + else if (1U == obj->_tag_) // uavcan.node.port.ServiceID.1.0 service_id + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 16ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 24ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/node/port/List_0_1.h b/hardware/include/uavcan/node/port/List_0_1.h new file mode 100644 index 0000000..7fcad1e --- /dev/null +++ b/hardware/include/uavcan/node/port/List_0_1.h @@ -0,0 +1,459 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/7510.List.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.125404 UTC +// Is deprecated: yes +// Fixed port-ID: 7510 +// Full name: uavcan.node.port.List +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32808ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 8200ULL); + // 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. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.port.SubjectIDList.0.1 subscribers + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32808ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 8200ULL); + // 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. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.port.ServiceIDList.0.1 clients + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 512ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.port.ServiceIDList.0.1 servers + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) == 512ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 128ULL); + NUNAVUT_ASSERT(offset_bits <= 67728ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_LIST_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/node/port/List_1_0.h b/hardware/include/uavcan/node/port/List_1_0.h new file mode 100644 index 0000000..f60df35 --- /dev/null +++ b/hardware/include/uavcan/node/port/List_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/7510.List.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.120726 UTC +// Is deprecated: no +// Fixed port-ID: 7510 +// Full name: uavcan.node.port.List +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32808ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes0_ * 8U) <= 8200ULL); + // 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. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.port.SubjectIDList.1.0 subscribers + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32808ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 1025UL; // Nested object (max) size, in bytes. + offset_bits += 32U; // Reserve space for the delimiter header. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) >= 8ULL); + NUNAVUT_ASSERT((_size_bytes1_ * 8U) <= 8200ULL); + // 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. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.port.ServiceIDList.1.0 clients + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes2_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes2_ * 8U) == 512ULL); + offset_bits += _size_bytes2_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.port.ServiceIDList.1.0 servers + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes3_) <= capacity_bytes); + 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. + NUNAVUT_ASSERT((_size_bytes3_ * 8U) == 512ULL); + offset_bits += _size_bytes3_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + if (offset_bits % 8U != 0U) // Pad to 8 bits. TODO: Eliminate redundant padding checks. + { + const uint8_t _pad3_ = (uint8_t)(8U - offset_bits % 8U); + NUNAVUT_ASSERT(_pad3_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad3_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad3_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 128ULL); + NUNAVUT_ASSERT(offset_bits <= 67728ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + // 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_LIST_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/port/ServiceIDList_0_1.h b/hardware/include/uavcan/node/port/ServiceIDList_0_1.h new file mode 100644 index 0000000..e6b58a8 --- /dev/null +++ b/hardware/include/uavcan/node/port/ServiceIDList_0_1.h @@ -0,0 +1,228 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/ServiceIDList.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.134771 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.node.port.ServiceIDList +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 512ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 512ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SERVICE_ID_LIST_0_1_INCLUDED_ + diff --git a/hardware/include/uavcan/node/port/ServiceIDList_1_0.h b/hardware/include/uavcan/node/port/ServiceIDList_1_0.h new file mode 100644 index 0000000..87cd696 --- /dev/null +++ b/hardware/include/uavcan/node/port/ServiceIDList_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/ServiceIDList.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.132304 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.ServiceIDList +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 512ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 512ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SERVICE_ID_LIST_1_0_INCLUDED_ + diff --git a/hardware/include/uavcan/node/port/ServiceID_1_0.h b/hardware/include/uavcan/node/port/ServiceID_1_0.h new file mode 100644 index 0000000..69e51f3 --- /dev/null +++ b/hardware/include/uavcan/node/port/ServiceID_1_0.h @@ -0,0 +1,220 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/ServiceID.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.129864 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.ServiceID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 9ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SERVICE_ID_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/node/port/SubjectIDList_0_1.h b/hardware/include/uavcan/node/port/SubjectIDList_0_1.h new file mode 100644 index 0000000..3ac7e92 --- /dev/null +++ b/hardware/include/uavcan/node/port/SubjectIDList_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/SubjectIDList.0.1.dsdl +// Generated at: 2025-07-17 18:00:19.143547 UTC +// Is deprecated: yes +// Fixed port-ID: None +// Full name: uavcan.node.port.SubjectIDList +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8192ULL) <= (capacity_bytes * 8U)); + // 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 4088ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->sparse_list.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + } + else if (2U == obj->_tag_) // uavcan.primitive.Empty.1.0 total + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 0ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 0UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 0ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 8200ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->sparse_list.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/node/port/SubjectIDList_1_0.h b/hardware/include/uavcan/node/port/SubjectIDList_1_0.h new file mode 100644 index 0000000..7b60234 --- /dev/null +++ b/hardware/include/uavcan/node/port/SubjectIDList_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/SubjectIDList.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.139478 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.SubjectIDList +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8192ULL) <= (capacity_bytes * 8U)); + // 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 4088ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->sparse_list.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + } + else if (2U == obj->_tag_) // uavcan.primitive.Empty.1.0 total + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 0ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 0UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 0ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 8200ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->sparse_list.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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/hardware/include/uavcan/node/port/SubjectID_1_0.h b/hardware/include/uavcan/node/port/SubjectID_1_0.h new file mode 100644 index 0000000..bc25b55 --- /dev/null +++ b/hardware/include/uavcan/node/port/SubjectID_1_0.h @@ -0,0 +1,220 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/node/port/SubjectID.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.137086 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.node.port.SubjectID +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 13ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_NODE_PORT_SUBJECT_ID_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/pnp/NodeIDAllocationData_1_0.h b/hardware/include/uavcan/pnp/NodeIDAllocationData_1_0.h new file mode 100644 index 0000000..ac7d103 --- /dev/null +++ b/hardware/include/uavcan/pnp/NodeIDAllocationData_1_0.h @@ -0,0 +1,304 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/pnp/8166.NodeIDAllocationData.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.028295 UTC +// Is deprecated: no +// Fixed port-ID: 8166 +// Full name: uavcan.pnp.NodeIDAllocationData +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 48ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.ID.1.0[<=1] allocated_node_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 24ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->allocated_node_id.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 56ULL); + NUNAVUT_ASSERT(offset_bits <= 72ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->allocated_node_id.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/pnp/NodeIDAllocationData_2_0.h b/hardware/include/uavcan/pnp/NodeIDAllocationData_2_0.h new file mode 100644 index 0000000..bd0e811 --- /dev/null +++ b/hardware/include/uavcan/pnp/NodeIDAllocationData_2_0.h @@ -0,0 +1,271 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/pnp/8165.NodeIDAllocationData.2.0.dsdl +// Generated at: 2025-07-17 18:00:19.025025 UTC +// Is deprecated: no +// Fixed port-ID: 8165 +// Full name: uavcan.pnp.NodeIDAllocationData +// Version: 2.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated uint8[16] unique_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 144ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 16UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_NODE_ID_ALLOCATION_DATA_2_0_INCLUDED_ + diff --git a/hardware/include/uavcan/pnp/cluster/AppendEntries_1_0.h b/hardware/include/uavcan/pnp/cluster/AppendEntries_1_0.h new file mode 100644 index 0000000..b2dabc5 --- /dev/null +++ b/hardware/include/uavcan/pnp/cluster/AppendEntries_1_0.h @@ -0,0 +1,537 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/pnp/cluster/390.AppendEntries.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.031632 UTC +// Is deprecated: no +// Fixed port-ID: 390 +// Full name: uavcan.pnp.cluster.AppendEntries +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err4_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err4_ < 0) + { + return _err4_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.pnp.cluster.Entry.1.0[<=1] entries + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 184ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->entries.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 176ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 22UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 176ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err6_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err6_ < 0) + { + return _err6_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 104ULL); + NUNAVUT_ASSERT(offset_bits <= 280ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint32 prev_log_term + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->prev_log_term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint16 prev_log_index + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->prev_log_index = nunavutGetU16(&buffer[0], capacity_bytes, offset_bits, 16); + offset_bits += 16U; + // saturated uint16 leader_commit + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->entries.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err9_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err9_ < 0) + { + return _err9_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 40ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated bool success + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_APPEND_ENTRIES_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/pnp/cluster/Discovery_1_0.h b/hardware/include/uavcan/pnp/cluster/Discovery_1_0.h new file mode 100644 index 0000000..657c4cc --- /dev/null +++ b/hardware/include/uavcan/pnp/cluster/Discovery_1_0.h @@ -0,0 +1,330 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/pnp/cluster/8164.Discovery.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.037241 UTC +// Is deprecated: no +// Fixed port-ID: 8164 +// Full name: uavcan.pnp.cluster.Discovery +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 3ULL) <= (capacity_bytes * 8U)); + 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 + NUNAVUT_ASSERT((offset_bits + 5ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.ID.1.0[<=5] known_nodes + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 88ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->known_nodes.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->known_nodes.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_DISCOVERY_1_0_INCLUDED_ + diff --git a/hardware/include/uavcan/pnp/cluster/Entry_1_0.h b/hardware/include/uavcan/pnp/cluster/Entry_1_0.h new file mode 100644 index 0000000..230f3a4 --- /dev/null +++ b/hardware/include/uavcan/pnp/cluster/Entry_1_0.h @@ -0,0 +1,301 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/pnp/cluster/Entry.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.040942 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.pnp.cluster.Entry +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 16UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.node.ID.1.0 node_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 16ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 176ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint8[16] unique_id + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 16UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_ENTRY_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/pnp/cluster/RequestVote_1_0.h b/hardware/include/uavcan/pnp/cluster/RequestVote_1_0.h new file mode 100644 index 0000000..70355a4 --- /dev/null +++ b/hardware/include/uavcan/pnp/cluster/RequestVote_1_0.h @@ -0,0 +1,421 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/pnp/cluster/391.RequestVote.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.044212 UTC +// Is deprecated: no +// Fixed port-ID: 391 +// Full name: uavcan.pnp.cluster.RequestVote +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 80ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint32 last_log_term + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->last_log_term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated uint16 last_log_index + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 40ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + out_obj->term = nunavutGetU32(&buffer[0], capacity_bytes, offset_bits, 32); + offset_bits += 32U; + // saturated bool vote_granted + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PNP_CLUSTER_REQUEST_VOTE_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/Empty_1_0.h b/hardware/include/uavcan/primitive/Empty_1_0.h new file mode 100644 index 0000000..ef3d1ca --- /dev/null +++ b/hardware/include/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/Empty.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.147564 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.Empty +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_EMPTY_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/String_1_0.h b/hardware/include/uavcan/primitive/String_1_0.h new file mode 100644 index 0000000..8ce82ae --- /dev/null +++ b/hardware/include/uavcan/primitive/String_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/String.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.149359 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.String +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_STRING_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/Unstructured_1_0.h b/hardware/include/uavcan/primitive/Unstructured_1_0.h new file mode 100644 index 0000000..a9941bc --- /dev/null +++ b/hardware/include/uavcan/primitive/Unstructured_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/Unstructured.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.152008 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.Unstructured +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_UNSTRUCTURED_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Bit_1_0.h b/hardware/include/uavcan/primitive/array/Bit_1_0.h new file mode 100644 index 0000000..e0d4505 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Bit_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Bit.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.183165 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Bit +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_BIT_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Integer16_1_0.h b/hardware/include/uavcan/primitive/array/Integer16_1_0.h new file mode 100644 index 0000000..a39ab75 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Integer16_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Integer16.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.185796 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER16_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Integer32_1_0.h b/hardware/include/uavcan/primitive/array/Integer32_1_0.h new file mode 100644 index 0000000..b9c3863 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Integer32_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Integer32.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.188587 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER32_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Integer64_1_0.h b/hardware/include/uavcan/primitive/array/Integer64_1_0.h new file mode 100644 index 0000000..ad77071 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Integer64_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Integer64.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.191367 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER64_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Integer8_1_0.h b/hardware/include/uavcan/primitive/array/Integer8_1_0.h new file mode 100644 index 0000000..c0e3d82 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Integer8_1_0.h @@ -0,0 +1,247 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Integer8.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.194067 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Integer8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_INTEGER8_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Natural16_1_0.h b/hardware/include/uavcan/primitive/array/Natural16_1_0.h new file mode 100644 index 0000000..efaff60 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Natural16_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Natural16.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.196770 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL16_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Natural32_1_0.h b/hardware/include/uavcan/primitive/array/Natural32_1_0.h new file mode 100644 index 0000000..eae2119 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Natural32_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Natural32.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.199570 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL32_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Natural64_1_0.h b/hardware/include/uavcan/primitive/array/Natural64_1_0.h new file mode 100644 index 0000000..b6530a7 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Natural64_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Natural64.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.202332 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL64_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Natural8_1_0.h b/hardware/include/uavcan/primitive/array/Natural8_1_0.h new file mode 100644 index 0000000..3b8b696 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Natural8_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Natural8.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.205053 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Natural8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2064ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 16ULL); + NUNAVUT_ASSERT(offset_bits <= 2064ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_NATURAL8_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Real16_1_0.h b/hardware/include/uavcan/primitive/array/Real16_1_0.h new file mode 100644 index 0000000..cb941fe --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Real16_1_0.h @@ -0,0 +1,264 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Real16.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.207793 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Real16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_REAL16_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Real32_1_0.h b/hardware/include/uavcan/primitive/array/Real32_1_0.h new file mode 100644 index 0000000..b299f55 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Real32_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Real32.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.210608 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Real32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_REAL32_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/array/Real64_1_0.h b/hardware/include/uavcan/primitive/array/Real64_1_0.h new file mode 100644 index 0000000..1959363 --- /dev/null +++ b/hardware/include/uavcan/primitive/array/Real64_1_0.h @@ -0,0 +1,254 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/array/Real64.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.213400 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.array.Real64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 2056ULL) <= (capacity_bytes * 8U)); + 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; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index0_ = 0U; _index0_ < obj->value.count; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits >= 8ULL); + NUNAVUT_ASSERT(offset_bits <= 2056ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + // 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; + } + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < out_obj->value.count; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_ARRAY_REAL64_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Bit_1_0.h b/hardware/include/uavcan/primitive/scalar/Bit_1_0.h new file mode 100644 index 0000000..bff421b --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Bit_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Bit.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.154629 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Bit +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 1ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_BIT_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Integer16_1_0.h b/hardware/include/uavcan/primitive/scalar/Integer16_1_0.h new file mode 100644 index 0000000..02993ae --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Integer16_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Integer16.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.156927 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER16_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Integer32_1_0.h b/hardware/include/uavcan/primitive/scalar/Integer32_1_0.h new file mode 100644 index 0000000..7d4c980 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Integer32_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Integer32.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.159345 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER32_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Integer64_1_0.h b/hardware/include/uavcan/primitive/scalar/Integer64_1_0.h new file mode 100644 index 0000000..9b84751 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Integer64_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Integer64.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.161869 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER64_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Integer8_1_0.h b/hardware/include/uavcan/primitive/scalar/Integer8_1_0.h new file mode 100644 index 0000000..cbbafc5 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Integer8_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Integer8.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.164179 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Integer8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_INTEGER8_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Natural16_1_0.h b/hardware/include/uavcan/primitive/scalar/Natural16_1_0.h new file mode 100644 index 0000000..21608e4 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Natural16_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Natural16.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.166509 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL16_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Natural32_1_0.h b/hardware/include/uavcan/primitive/scalar/Natural32_1_0.h new file mode 100644 index 0000000..e8ac03c --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Natural32_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Natural32.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.168758 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL32_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Natural64_1_0.h b/hardware/include/uavcan/primitive/scalar/Natural64_1_0.h new file mode 100644 index 0000000..fd6c18d --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Natural64_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Natural64.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.171276 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL64_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Natural8_1_0.h b/hardware/include/uavcan/primitive/scalar/Natural8_1_0.h new file mode 100644 index 0000000..8978a6c --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Natural8_1_0.h @@ -0,0 +1,216 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Natural8.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.173614 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Natural8 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_NATURAL8_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Real16_1_0.h b/hardware/include/uavcan/primitive/scalar/Real16_1_0.h new file mode 100644 index 0000000..413e773 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Real16_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Real16.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.175915 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Real16 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_REAL16_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Real32_1_0.h b/hardware/include/uavcan/primitive/scalar/Real32_1_0.h new file mode 100644 index 0000000..5cfb128 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Real32_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Real32.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.178459 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Real32 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_REAL32_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/primitive/scalar/Real64_1_0.h b/hardware/include/uavcan/primitive/scalar/Real64_1_0.h new file mode 100644 index 0000000..129bf38 --- /dev/null +++ b/hardware/include/uavcan/primitive/scalar/Real64_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/primitive/scalar/Real64.1.0.dsdl +// Generated at: 2025-07-17 18:00:19.180771 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.primitive.scalar.Real64 +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_PRIMITIVE_SCALAR_REAL64_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/acceleration/Scalar_1_0.h b/hardware/include/uavcan/si/sample/acceleration/Scalar_1_0.h new file mode 100644 index 0000000..8deaf91 --- /dev/null +++ b/hardware/include/uavcan/si/sample/acceleration/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/acceleration/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.883019 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 meter_per_second_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/acceleration/Vector3_1_0.h b/hardware/include/uavcan/si/sample/acceleration/Vector3_1_0.h new file mode 100644 index 0000000..7b5a3b9 --- /dev/null +++ b/hardware/include/uavcan/si/sample/acceleration/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/acceleration/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.886744 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] meter_per_second_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/angle/Quaternion_1_0.h b/hardware/include/uavcan/si/sample/angle/Quaternion_1_0.h new file mode 100644 index 0000000..9d5c8be --- /dev/null +++ b/hardware/include/uavcan/si/sample/angle/Quaternion_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/angle/Quaternion.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.940680 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[4] wxyz + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 4UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 184ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 4UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGLE_QUATERNION_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/angle/Scalar_1_0.h b/hardware/include/uavcan/si/sample/angle/Scalar_1_0.h new file mode 100644 index 0000000..434d92d --- /dev/null +++ b/hardware/include/uavcan/si/sample/angle/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/angle/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.943694 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 radian + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGLE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/angular_acceleration/Scalar_1_0.h b/hardware/include/uavcan/si/sample/angular_acceleration/Scalar_1_0.h new file mode 100644 index 0000000..1b14f02 --- /dev/null +++ b/hardware/include/uavcan/si/sample/angular_acceleration/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/angular_acceleration/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.958343 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 radian_per_second_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/angular_acceleration/Vector3_1_0.h b/hardware/include/uavcan/si/sample/angular_acceleration/Vector3_1_0.h new file mode 100644 index 0000000..e215ff2 --- /dev/null +++ b/hardware/include/uavcan/si/sample/angular_acceleration/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/angular_acceleration/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.961232 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] radian_per_second_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/angular_velocity/Scalar_1_0.h b/hardware/include/uavcan/si/sample/angular_velocity/Scalar_1_0.h new file mode 100644 index 0000000..5cbaaef --- /dev/null +++ b/hardware/include/uavcan/si/sample/angular_velocity/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/angular_velocity/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.853996 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 radian_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/angular_velocity/Vector3_1_0.h b/hardware/include/uavcan/si/sample/angular_velocity/Vector3_1_0.h new file mode 100644 index 0000000..dda8d7b --- /dev/null +++ b/hardware/include/uavcan/si/sample/angular_velocity/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/angular_velocity/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.856919 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] radian_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/duration/Scalar_1_0.h b/hardware/include/uavcan/si/sample/duration/Scalar_1_0.h new file mode 100644 index 0000000..977ee71 --- /dev/null +++ b/hardware/include/uavcan/si/sample/duration/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/duration/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.920334 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_DURATION_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/duration/WideScalar_1_0.h b/hardware/include/uavcan/si/sample/duration/WideScalar_1_0.h new file mode 100644 index 0000000..1952bda --- /dev/null +++ b/hardware/include/uavcan/si/sample/duration/WideScalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/duration/WideScalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.923706 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float64 second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 120ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_DURATION_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/electric_charge/Scalar_1_0.h b/hardware/include/uavcan/si/sample/electric_charge/Scalar_1_0.h new file mode 100644 index 0000000..8602e2f --- /dev/null +++ b/hardware/include/uavcan/si/sample/electric_charge/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/electric_charge/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.937948 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 coulomb + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/electric_current/Scalar_1_0.h b/hardware/include/uavcan/si/sample/electric_current/Scalar_1_0.h new file mode 100644 index 0000000..aa0d5e9 --- /dev/null +++ b/hardware/include/uavcan/si/sample/electric_current/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/electric_current/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.877345 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 ampere + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/energy/Scalar_1_0.h b/hardware/include/uavcan/si/sample/energy/Scalar_1_0.h new file mode 100644 index 0000000..7ce4486 --- /dev/null +++ b/hardware/include/uavcan/si/sample/energy/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/energy/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.926693 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 joule + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_ENERGY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/force/Scalar_1_0.h b/hardware/include/uavcan/si/sample/force/Scalar_1_0.h new file mode 100644 index 0000000..49d6acc --- /dev/null +++ b/hardware/include/uavcan/si/sample/force/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/force/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.892655 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 newton + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_FORCE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/force/Vector3_1_0.h b/hardware/include/uavcan/si/sample/force/Vector3_1_0.h new file mode 100644 index 0000000..c10d445 --- /dev/null +++ b/hardware/include/uavcan/si/sample/force/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/force/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.895407 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] newton + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_FORCE_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/frequency/Scalar_1_0.h b/hardware/include/uavcan/si/sample/frequency/Scalar_1_0.h new file mode 100644 index 0000000..9698a0a --- /dev/null +++ b/hardware/include/uavcan/si/sample/frequency/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/frequency/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.874493 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 hertz + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_FREQUENCY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/length/Scalar_1_0.h b/hardware/include/uavcan/si/sample/length/Scalar_1_0.h new file mode 100644 index 0000000..6a53cb6 --- /dev/null +++ b/hardware/include/uavcan/si/sample/length/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/length/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.946525 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/length/Vector3_1_0.h b/hardware/include/uavcan/si/sample/length/Vector3_1_0.h new file mode 100644 index 0000000..a69097e --- /dev/null +++ b/hardware/include/uavcan/si/sample/length/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/length/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.949332 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/length/WideScalar_1_0.h b/hardware/include/uavcan/si/sample/length/WideScalar_1_0.h new file mode 100644 index 0000000..c5742bd --- /dev/null +++ b/hardware/include/uavcan/si/sample/length/WideScalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/length/WideScalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.952364 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float64 meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 120ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/length/WideVector3_1_0.h b/hardware/include/uavcan/si/sample/length/WideVector3_1_0.h new file mode 100644 index 0000000..19d4133 --- /dev/null +++ b/hardware/include/uavcan/si/sample/length/WideVector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/length/WideVector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.955229 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float64[3] meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 192ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 248ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/luminance/Scalar_1_0.h b/hardware/include/uavcan/si/sample/luminance/Scalar_1_0.h new file mode 100644 index 0000000..ee3f7f8 --- /dev/null +++ b/hardware/include/uavcan/si/sample/luminance/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/luminance/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.913358 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 candela_per_square_meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_LUMINANCE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h b/hardware/include/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h new file mode 100644 index 0000000..f250be8 --- /dev/null +++ b/hardware/include/uavcan/si/sample/magnetic_field_strength/Scalar_1_0.h @@ -0,0 +1,258 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.862844 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 tesla + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.h b/hardware/include/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.h new file mode 100644 index 0000000..82fe4bc --- /dev/null +++ b/hardware/include/uavcan/si/sample/magnetic_field_strength/Scalar_1_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/magnetic_field_strength/Scalar.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.859979 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 ampere_per_meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h b/hardware/include/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h new file mode 100644 index 0000000..46432ac --- /dev/null +++ b/hardware/include/uavcan/si/sample/magnetic_field_strength/Vector3_1_0.h @@ -0,0 +1,276 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.868683 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] tesla + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h b/hardware/include/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h new file mode 100644 index 0000000..ca53b3d --- /dev/null +++ b/hardware/include/uavcan/si/sample/magnetic_field_strength/Vector3_1_1.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/magnetic_field_strength/Vector3.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.865671 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] ampere_per_meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/magnetic_flux_density/Scalar_1_0.h b/hardware/include/uavcan/si/sample/magnetic_flux_density/Scalar_1_0.h new file mode 100644 index 0000000..bb51141 --- /dev/null +++ b/hardware/include/uavcan/si/sample/magnetic_flux_density/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/magnetic_flux_density/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.964253 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 tesla + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h b/hardware/include/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h new file mode 100644 index 0000000..837262d --- /dev/null +++ b/hardware/include/uavcan/si/sample/magnetic_flux_density/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/magnetic_flux_density/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.967052 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] tesla + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/mass/Scalar_1_0.h b/hardware/include/uavcan/si/sample/mass/Scalar_1_0.h new file mode 100644 index 0000000..3223c34 --- /dev/null +++ b/hardware/include/uavcan/si/sample/mass/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/mass/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.916891 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 kilogram + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_MASS_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/power/Scalar_1_0.h b/hardware/include/uavcan/si/sample/power/Scalar_1_0.h new file mode 100644 index 0000000..4fcf869 --- /dev/null +++ b/hardware/include/uavcan/si/sample/power/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/power/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.889857 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 watt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_POWER_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/pressure/Scalar_1_0.h b/hardware/include/uavcan/si/sample/pressure/Scalar_1_0.h new file mode 100644 index 0000000..05b40dc --- /dev/null +++ b/hardware/include/uavcan/si/sample/pressure/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/pressure/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.871685 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 pascal + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_PRESSURE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/temperature/Scalar_1_0.h b/hardware/include/uavcan/si/sample/temperature/Scalar_1_0.h new file mode 100644 index 0000000..cc5bf33 --- /dev/null +++ b/hardware/include/uavcan/si/sample/temperature/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/temperature/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.880155 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 kelvin + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_TEMPERATURE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/torque/Scalar_1_0.h b/hardware/include/uavcan/si/sample/torque/Scalar_1_0.h new file mode 100644 index 0000000..6162ce2 --- /dev/null +++ b/hardware/include/uavcan/si/sample/torque/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/torque/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.905710 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 newton_meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_TORQUE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/torque/Vector3_1_0.h b/hardware/include/uavcan/si/sample/torque/Vector3_1_0.h new file mode 100644 index 0000000..2d02ed4 --- /dev/null +++ b/hardware/include/uavcan/si/sample/torque/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/torque/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.909436 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] newton_meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_TORQUE_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/velocity/Scalar_1_0.h b/hardware/include/uavcan/si/sample/velocity/Scalar_1_0.h new file mode 100644 index 0000000..9c4d0a7 --- /dev/null +++ b/hardware/include/uavcan/si/sample/velocity/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/velocity/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.898442 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 meter_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/velocity/Vector3_1_0.h b/hardware/include/uavcan/si/sample/velocity/Vector3_1_0.h new file mode 100644 index 0000000..dfa9ca6 --- /dev/null +++ b/hardware/include/uavcan/si/sample/velocity/Vector3_1_0.h @@ -0,0 +1,267 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/velocity/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.901261 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32[3] meter_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 152ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/voltage/Scalar_1_0.h b/hardware/include/uavcan/si/sample/voltage/Scalar_1_0.h new file mode 100644 index 0000000..a114265 --- /dev/null +++ b/hardware/include/uavcan/si/sample/voltage/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/voltage/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.929488 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 volt + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VOLTAGE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/volume/Scalar_1_0.h b/hardware/include/uavcan/si/sample/volume/Scalar_1_0.h new file mode 100644 index 0000000..961837d --- /dev/null +++ b/hardware/include/uavcan/si/sample/volume/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/volume/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.935183 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 cubic_meter + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VOLUME_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/sample/volumetric_flow_rate/Scalar_1_0.h b/hardware/include/uavcan/si/sample/volumetric_flow_rate/Scalar_1_0.h new file mode 100644 index 0000000..0c2ec89 --- /dev/null +++ b/hardware/include/uavcan/si/sample/volumetric_flow_rate/Scalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.932331 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 7UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 56ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 8U)); + } + { // saturated float32 cubic_meter_per_second + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err2_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err2_ < 0) + { + return _err2_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 88ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes1_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_SAMPLE_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/acceleration/Scalar_1_0.h b/hardware/include/uavcan/si/unit/acceleration/Scalar_1_0.h new file mode 100644 index 0000000..be61b5b --- /dev/null +++ b/hardware/include/uavcan/si/unit/acceleration/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/acceleration/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.831358 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/acceleration/Vector3_1_0.h b/hardware/include/uavcan/si/unit/acceleration/Vector3_1_0.h new file mode 100644 index 0000000..5a2b416 --- /dev/null +++ b/hardware/include/uavcan/si/unit/acceleration/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/acceleration/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.833804 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/angle/Quaternion_1_0.h b/hardware/include/uavcan/si/unit/angle/Quaternion_1_0.h new file mode 100644 index 0000000..cb8133d --- /dev/null +++ b/hardware/include/uavcan/si/unit/angle/Quaternion_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/angle/Quaternion.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.823936 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 128ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 4UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 128ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 128ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 4UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGLE_QUATERNION_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/angle/Scalar_1_0.h b/hardware/include/uavcan/si/unit/angle/Scalar_1_0.h new file mode 100644 index 0000000..918c9f3 --- /dev/null +++ b/hardware/include/uavcan/si/unit/angle/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/angle/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.826614 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGLE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/angular_acceleration/Scalar_1_0.h b/hardware/include/uavcan/si/unit/angular_acceleration/Scalar_1_0.h new file mode 100644 index 0000000..9526734 --- /dev/null +++ b/hardware/include/uavcan/si/unit/angular_acceleration/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/angular_acceleration/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.789111 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/angular_acceleration/Vector3_1_0.h b/hardware/include/uavcan/si/unit/angular_acceleration/Vector3_1_0.h new file mode 100644 index 0000000..624eebc --- /dev/null +++ b/hardware/include/uavcan/si/unit/angular_acceleration/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/angular_acceleration/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.791598 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_ACCELERATION_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/angular_velocity/Scalar_1_0.h b/hardware/include/uavcan/si/unit/angular_velocity/Scalar_1_0.h new file mode 100644 index 0000000..bc9e639 --- /dev/null +++ b/hardware/include/uavcan/si/unit/angular_velocity/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/angular_velocity/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.760084 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/angular_velocity/Vector3_1_0.h b/hardware/include/uavcan/si/unit/angular_velocity/Vector3_1_0.h new file mode 100644 index 0000000..aaeba22 --- /dev/null +++ b/hardware/include/uavcan/si/unit/angular_velocity/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/angular_velocity/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.763635 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ANGULAR_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/duration/Scalar_1_0.h b/hardware/include/uavcan/si/unit/duration/Scalar_1_0.h new file mode 100644 index 0000000..9788737 --- /dev/null +++ b/hardware/include/uavcan/si/unit/duration/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/duration/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.752839 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_DURATION_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/duration/WideScalar_1_0.h b/hardware/include/uavcan/si/unit/duration/WideScalar_1_0.h new file mode 100644 index 0000000..a4f6d30 --- /dev/null +++ b/hardware/include/uavcan/si/unit/duration/WideScalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/duration/WideScalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.754499 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_DURATION_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/electric_charge/Scalar_1_0.h b/hardware/include/uavcan/si/unit/electric_charge/Scalar_1_0.h new file mode 100644 index 0000000..d2a96ba --- /dev/null +++ b/hardware/include/uavcan/si/unit/electric_charge/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/electric_charge/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.786188 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ELECTRIC_CHARGE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/electric_current/Scalar_1_0.h b/hardware/include/uavcan/si/unit/electric_current/Scalar_1_0.h new file mode 100644 index 0000000..1a81682 --- /dev/null +++ b/hardware/include/uavcan/si/unit/electric_current/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/electric_current/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.803894 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ELECTRIC_CURRENT_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/energy/Scalar_1_0.h b/hardware/include/uavcan/si/unit/energy/Scalar_1_0.h new file mode 100644 index 0000000..778e238 --- /dev/null +++ b/hardware/include/uavcan/si/unit/energy/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/energy/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.851579 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_ENERGY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/force/Scalar_1_0.h b/hardware/include/uavcan/si/unit/force/Scalar_1_0.h new file mode 100644 index 0000000..0fdac55 --- /dev/null +++ b/hardware/include/uavcan/si/unit/force/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/force/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.838877 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_FORCE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/force/Vector3_1_0.h b/hardware/include/uavcan/si/unit/force/Vector3_1_0.h new file mode 100644 index 0000000..e8f201b --- /dev/null +++ b/hardware/include/uavcan/si/unit/force/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/force/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.841418 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_FORCE_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/frequency/Scalar_1_0.h b/hardware/include/uavcan/si/unit/frequency/Scalar_1_0.h new file mode 100644 index 0000000..0cb89f4 --- /dev/null +++ b/hardware/include/uavcan/si/unit/frequency/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/frequency/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.756374 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_FREQUENCY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/length/Scalar_1_0.h b/hardware/include/uavcan/si/unit/length/Scalar_1_0.h new file mode 100644 index 0000000..8fe8952 --- /dev/null +++ b/hardware/include/uavcan/si/unit/length/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/length/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.813852 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/length/Vector3_1_0.h b/hardware/include/uavcan/si/unit/length/Vector3_1_0.h new file mode 100644 index 0000000..ef36b17 --- /dev/null +++ b/hardware/include/uavcan/si/unit/length/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/length/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.816374 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/length/WideScalar_1_0.h b/hardware/include/uavcan/si/unit/length/WideScalar_1_0.h new file mode 100644 index 0000000..7a08138 --- /dev/null +++ b/hardware/include/uavcan/si/unit/length/WideScalar_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/length/WideScalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.818900 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 64ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_WIDE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/length/WideVector3_1_0.h b/hardware/include/uavcan/si/unit/length/WideVector3_1_0.h new file mode 100644 index 0000000..aed9424 --- /dev/null +++ b/hardware/include/uavcan/si/unit/length/WideVector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/length/WideVector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.821343 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 192ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 64ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 192ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 192ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LENGTH_WIDE_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/luminance/Scalar_1_0.h b/hardware/include/uavcan/si/unit/luminance/Scalar_1_0.h new file mode 100644 index 0000000..3dc68c3 --- /dev/null +++ b/hardware/include/uavcan/si/unit/luminance/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/luminance/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.811358 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_LUMINANCE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h b/hardware/include/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h new file mode 100644 index 0000000..bb4be22 --- /dev/null +++ b/hardware/include/uavcan/si/unit/magnetic_field_strength/Scalar_1_0.h @@ -0,0 +1,222 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.776743 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/magnetic_field_strength/Scalar_1_1.h b/hardware/include/uavcan/si/unit/magnetic_field_strength/Scalar_1_1.h new file mode 100644 index 0000000..74f8e34 --- /dev/null +++ b/hardware/include/uavcan/si/unit/magnetic_field_strength/Scalar_1_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/magnetic_field_strength/Scalar.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.773684 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_SCALAR_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h b/hardware/include/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h new file mode 100644 index 0000000..4fb9702 --- /dev/null +++ b/hardware/include/uavcan/si/unit/magnetic_field_strength/Vector3_1_0.h @@ -0,0 +1,240 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.782803 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/magnetic_field_strength/Vector3_1_1.h b/hardware/include/uavcan/si/unit/magnetic_field_strength/Vector3_1_1.h new file mode 100644 index 0000000..cbc67ac --- /dev/null +++ b/hardware/include/uavcan/si/unit/magnetic_field_strength/Vector3_1_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/magnetic_field_strength/Vector3.1.1.dsdl +// Generated at: 2025-07-17 18:00:18.779648 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FIELD_STRENGTH_VECTOR3_1_1_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/magnetic_flux_density/Scalar_1_0.h b/hardware/include/uavcan/si/unit/magnetic_flux_density/Scalar_1_0.h new file mode 100644 index 0000000..5906748 --- /dev/null +++ b/hardware/include/uavcan/si/unit/magnetic_flux_density/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/magnetic_flux_density/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.846484 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.h b/hardware/include/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.h new file mode 100644 index 0000000..dc68a32 --- /dev/null +++ b/hardware/include/uavcan/si/unit/magnetic_flux_density/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/magnetic_flux_density/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.848898 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MAGNETIC_FLUX_DENSITY_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/mass/Scalar_1_0.h b/hardware/include/uavcan/si/unit/mass/Scalar_1_0.h new file mode 100644 index 0000000..ca128a5 --- /dev/null +++ b/hardware/include/uavcan/si/unit/mass/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/mass/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.794323 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_MASS_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/power/Scalar_1_0.h b/hardware/include/uavcan/si/unit/power/Scalar_1_0.h new file mode 100644 index 0000000..f5d55d0 --- /dev/null +++ b/hardware/include/uavcan/si/unit/power/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/power/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.767699 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_POWER_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/pressure/Scalar_1_0.h b/hardware/include/uavcan/si/unit/pressure/Scalar_1_0.h new file mode 100644 index 0000000..e900c30 --- /dev/null +++ b/hardware/include/uavcan/si/unit/pressure/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/pressure/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.836422 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_PRESSURE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/temperature/Scalar_1_0.h b/hardware/include/uavcan/si/unit/temperature/Scalar_1_0.h new file mode 100644 index 0000000..5653af9 --- /dev/null +++ b/hardware/include/uavcan/si/unit/temperature/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/temperature/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.829035 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_TEMPERATURE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/torque/Scalar_1_0.h b/hardware/include/uavcan/si/unit/torque/Scalar_1_0.h new file mode 100644 index 0000000..afe03ef --- /dev/null +++ b/hardware/include/uavcan/si/unit/torque/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/torque/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.806219 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_TORQUE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/torque/Vector3_1_0.h b/hardware/include/uavcan/si/unit/torque/Vector3_1_0.h new file mode 100644 index 0000000..784f317 --- /dev/null +++ b/hardware/include/uavcan/si/unit/torque/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/torque/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.808684 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_TORQUE_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/velocity/Scalar_1_0.h b/hardware/include/uavcan/si/unit/velocity/Scalar_1_0.h new file mode 100644 index 0000000..6d77e7c --- /dev/null +++ b/hardware/include/uavcan/si/unit/velocity/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/velocity/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.799012 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VELOCITY_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/velocity/Vector3_1_0.h b/hardware/include/uavcan/si/unit/velocity/Vector3_1_0.h new file mode 100644 index 0000000..e027dcc --- /dev/null +++ b/hardware/include/uavcan/si/unit/velocity/Vector3_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/velocity/Vector3.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.801353 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 96ULL) <= (capacity_bytes * 8U)); + const size_t _origin0_ = offset_bits; + for (size_t _index0_ = 0U; _index0_ < 3UL; ++_index0_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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. + NUNAVUT_ASSERT((offset_bits - _origin0_) == 96ULL); + (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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 96ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + for (size_t _index1_ = 0U; _index1_ < 3UL; ++_index1_) + { + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VELOCITY_VECTOR3_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/voltage/Scalar_1_0.h b/hardware/include/uavcan/si/unit/voltage/Scalar_1_0.h new file mode 100644 index 0000000..f84a410 --- /dev/null +++ b/hardware/include/uavcan/si/unit/voltage/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/voltage/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.770721 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VOLTAGE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/volume/Scalar_1_0.h b/hardware/include/uavcan/si/unit/volume/Scalar_1_0.h new file mode 100644 index 0000000..afc3f22 --- /dev/null +++ b/hardware/include/uavcan/si/unit/volume/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/volume/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.796686 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VOLUME_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/si/unit/volumetric_flow_rate/Scalar_1_0.h b/hardware/include/uavcan/si/unit/volumetric_flow_rate/Scalar_1_0.h new file mode 100644 index 0000000..04d8a9b --- /dev/null +++ b/hardware/include/uavcan/si/unit/volumetric_flow_rate/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.844011 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.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 32ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_SI_UNIT_VOLUMETRIC_FLOW_RATE_SCALAR_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/time/GetSynchronizationMasterInfo_0_1.h b/hardware/include/uavcan/time/GetSynchronizationMasterInfo_0_1.h new file mode 100644 index 0000000..f0c113c --- /dev/null +++ b/hardware/include/uavcan/time/GetSynchronizationMasterInfo_0_1.h @@ -0,0 +1,417 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/time/510.GetSynchronizationMasterInfo.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.744317 UTC +// Is deprecated: no +// Fixed port-ID: 510 +// Full name: uavcan.time.GetSynchronizationMasterInfo +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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); + NUNAVUT_ASSERT(err >= 0); + (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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 32ULL) <= (capacity_bytes * 8U)); + // 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.time.TimeSystem.0.1 time_system + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 8ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes0_ = 1UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes0_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes0_ * 8U) == 8ULL); + offset_bits += _size_bytes0_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad1_ > 0); + const int8_t _err3_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad1_); // Optimize? + if (_err3_ < 0) + { + return _err3_; + } + offset_bits += _pad1_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + { // uavcan.time.TAIInfo.0.1 tai_info + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 16ULL) <= (capacity_bytes * 8U)); + size_t _size_bytes1_ = 2UL; // Nested object (max) size, in bytes. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits / 8U + _size_bytes1_) <= capacity_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. + NUNAVUT_ASSERT((_size_bytes1_ * 8U) == 16ULL); + offset_bits += _size_bytes1_ * 8U; // Advance by the size of the nested object. + NUNAVUT_ASSERT(offset_bits <= (capacity_bytes * 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); + NUNAVUT_ASSERT(_pad2_ > 0); + const int8_t _err5_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad2_); // Optimize? + if (_err5_ < 0) + { + return _err5_; + } + offset_bits += _pad2_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 56ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes2_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + { + size_t _size_bytes3_ = (size_t)(capacity_bytes - nunavutChooseMin((offset_bits / 8U), capacity_bytes)); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_GET_SYNCHRONIZATION_MASTER_INFO_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/time/Synchronization_1_0.h b/hardware/include/uavcan/time/Synchronization_1_0.h new file mode 100644 index 0000000..994e759 --- /dev/null +++ b/hardware/include/uavcan/time/Synchronization_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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/time/7168.Synchronization.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.746816 UTC +// Is deprecated: no +// Fixed port-ID: 7168 +// Full name: uavcan.time.Synchronization +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 56ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_SYNCHRONIZATION_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/time/SynchronizedTimestamp_1_0.h b/hardware/include/uavcan/time/SynchronizedTimestamp_1_0.h new file mode 100644 index 0000000..d998ea0 --- /dev/null +++ b/hardware/include/uavcan/time/SynchronizedTimestamp_1_0.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/time/SynchronizedTimestamp.1.0.dsdl +// Generated at: 2025-07-17 18:00:18.748268 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.time.SynchronizedTimestamp +// Version: 1.0 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 56ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 56ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_SYNCHRONIZED_TIMESTAMP_1_0_INCLUDED_ diff --git a/hardware/include/uavcan/time/TAIInfo_0_1.h b/hardware/include/uavcan/time/TAIInfo_0_1.h new file mode 100644 index 0000000..71ccced --- /dev/null +++ b/hardware/include/uavcan/time/TAIInfo_0_1.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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/time/TAIInfo.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.749808 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.time.TAIInfo +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 10ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err1_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err1_ < 0) + { + return _err1_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 16ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_TAI_INFO_0_1_INCLUDED_ diff --git a/hardware/include/uavcan/time/TimeSystem_0_1.h b/hardware/include/uavcan/time/TimeSystem_0_1.h new file mode 100644 index 0000000..345b892 --- /dev/null +++ b/hardware/include/uavcan/time/TimeSystem_0_1.h @@ -0,0 +1,224 @@ +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/uavcan/time/TimeSystem.0.1.dsdl +// Generated at: 2025-07-17 18:00:18.751295 UTC +// Is deprecated: no +// Fixed port-ID: None +// Full name: uavcan.time.TimeSystem +// Version: 0.1 +// +// Platform +// python_implementation: CPython +// python_version: 3.13.5 +// python_release_level: final +// python_build: ('main', 'Jun 21 2025 09:35:00') +// python_compiler: GCC 15.1.1 20250425 +// python_revision: +// python_xoptions: {} +// runtime_platform: Linux-6.15.6-arch1-1-x86_64-with-glibc2.41 +// +// Language Options +// target_endianness: any +// omit_float_serialization_support: False +// enable_serialization_asserts: True +// 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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 == 1, + "/home/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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/nils/development/N17BLDC/fw/.pio/libdeps/nilsdriverv1/public_regulated_data_types/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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + NUNAVUT_ASSERT((offset_bits + 4ULL) <= (capacity_bytes * 8U)); + 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); + NUNAVUT_ASSERT(_pad0_ > 0); + const int8_t _err0_ = nunavutSetUxx(&buffer[0], capacity_bytes, offset_bits, 0U, _pad0_); // Optimize? + if (_err0_ < 0) + { + return _err0_; + } + offset_bits += _pad0_; + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + } + // It is assumed that we know the exact type of the serialized entity, hence we expect the size to match. + NUNAVUT_ASSERT(offset_bits == 8ULL); + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *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 + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + 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. + NUNAVUT_ASSERT(offset_bits % 8U == 0U); + *inout_buffer_size_bytes = (size_t) (nunavutChooseMin(offset_bits, capacity_bits) / 8U); + NUNAVUT_ASSERT(capacity_bytes >= *inout_buffer_size_bytes); + 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); + NUNAVUT_ASSERT(err >= 0); + (void) err; + } +} + +#ifdef __cplusplus +} +#endif +#endif // UAVCAN_TIME_TIME_SYSTEM_0_1_INCLUDED_ diff --git a/hardware/socketcan.cpp b/hardware/socketcan.cpp new file mode 100644 index 0000000..0bba7c9 --- /dev/null +++ b/hardware/socketcan.cpp @@ -0,0 +1,302 @@ +/// This software is distributed under the terms of the MIT License. +/// Copyright (C) OpenCyphal Development Team +/// Copyright Amazon.com Inc. or its affiliates. +/// SPDX-License-Identifier: MIT +/// Authors: Pavel Kirienko , Tom De Rybel + +// This is needed to enable the necessary declarations in sys/ +#ifndef _GNU_SOURCE +# define _GNU_SOURCE +#endif + +#include "socketcan.h" + +#ifdef __linux__ +# include +# include +# include +# include +# include +#else +# error "Unsupported OS -- feel free to add support for your OS here. " \ + "Zephyr and NuttX are known to support the SocketCAN API." +#endif + +#include +#include +#include +#include +#include +#include + +#define KILO 1000L +#define MEGA (KILO * KILO) + +static int16_t getNegatedErrno(void) +{ + const int out = -abs(errno); + if (out < 0) + { + if (out >= INT16_MIN) + { + return (int16_t) out; + } + } + else + { + assert(false); // Requested an error when errno is zero? + } + return INT16_MIN; +} + +static int16_t doPoll(const SocketCANFD fd, const int16_t mask, const CanardMicrosecond timeout_usec) +{ + struct pollfd fds; + memset(&fds, 0, sizeof(fds)); + fds.fd = fd; + fds.events = mask; + + struct timespec ts; + ts.tv_sec = (long) (timeout_usec / (CanardMicrosecond) MEGA); + ts.tv_nsec = (long) (timeout_usec % (CanardMicrosecond) MEGA) * KILO; + + const int poll_result = ppoll(&fds, 1, &ts, NULL); + if (poll_result < 0) + { + return getNegatedErrno(); + } + if (poll_result == 0) + { + return 0; + } + if (((uint32_t) fds.revents & (uint32_t) mask) == 0) + { + return -EIO; + } + + return 1; +} + +SocketCANFD socketcanOpen(const char* const iface_name, const size_t can_mtu) +{ + const size_t iface_name_size = strlen(iface_name) + 1; + if (iface_name_size > IFNAMSIZ) + { + return -ENAMETOOLONG; + } + + const int fd = socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW); // NOLINT + bool ok = fd >= 0; + + if (ok) + { + struct ifreq ifr; + (void) memset(&ifr, 0, sizeof(ifr)); + (void) memcpy(ifr.ifr_name, iface_name, iface_name_size); + ok = 0 == ioctl(fd, SIOCGIFINDEX, &ifr); + if (ok) + { + struct sockaddr_can addr; + (void) memset(&addr, 0, sizeof(addr)); + addr.can_family = AF_CAN; + addr.can_ifindex = ifr.ifr_ifindex; + ok = 0 == bind(fd, (struct sockaddr*) &addr, sizeof(addr)); + } + } + + // Enable CAN FD if required. + if (ok && (can_mtu > CAN_MAX_DLEN)) + { + const int en = 1; + ok = 0 == setsockopt(fd, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &en, sizeof(en)); + } + + // Enable timestamping. + if (ok) + { + const int en = 1; + ok = 0 == setsockopt(fd, SOL_SOCKET, SO_TIMESTAMP, &en, sizeof(en)); + } + + // Enable outgoing-frame loop-back. + if (ok) + { + const int en = 1; + ok = 0 == setsockopt(fd, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &en, sizeof(en)); + } + + if (ok) + { + return fd; + } + + (void) close(fd); + return getNegatedErrno(); +} + +int16_t socketcanPush(const SocketCANFD fd, const struct CanardFrame* const frame, const CanardMicrosecond timeout_usec) +{ + if ((frame == NULL) || (frame->payload.data == NULL) || (frame->payload.size > UINT8_MAX)) + { + return -EINVAL; + } + + const int16_t poll_result = doPoll(fd, POLLOUT, timeout_usec); + if (poll_result > 0) + { + // We use the CAN FD struct regardless of whether the CAN FD socket option is set. + // Per the user manual, this is acceptable because they are binary compatible. + struct canfd_frame cfd; + (void) memset(&cfd, 0, sizeof(cfd)); + cfd.can_id = frame->extended_can_id | CAN_EFF_FLAG; + cfd.len = (uint8_t) frame->payload.size; + // We set the bit rate switch on the assumption that it will be ignored by non-CAN-FD-capable hardware. + cfd.flags = CANFD_BRS; + (void) memcpy(cfd.data, frame->payload.data, frame->payload.size); + + // If the payload is small, use the smaller MTU for compatibility with non-FD sockets. + // This way, if the user attempts to transmit a CAN FD frame without having the CAN FD socket option enabled, + // an error will be triggered here. This is convenient -- we can handle both FD and Classic CAN uniformly. + const size_t mtu = (frame->payload.size > CAN_MAX_DLEN) ? CANFD_MTU : CAN_MTU; + if (write(fd, &cfd, mtu) < 0) + { + return getNegatedErrno(); + } + } + return poll_result; +} + +int16_t socketcanPop(const SocketCANFD fd, + struct CanardFrame* const out_frame, + CanardMicrosecond* const out_timestamp_usec, + const size_t payload_buffer_size, + void* const payload_buffer, + const CanardMicrosecond timeout_usec, + bool* const loopback) +{ + if ((out_frame == NULL) || (payload_buffer == NULL)) + { + return -EINVAL; + } + + const int16_t poll_result = doPoll(fd, POLLIN, timeout_usec); + if (poll_result > 0) + { + // Initialize the message header scatter/gather array. It is to hold a single CAN FD frame struct. + // We use the CAN FD struct regardless of whether the CAN FD socket option is set. + // Per the user manual, this is acceptable because they are binary compatible. + struct canfd_frame sockcan_frame; // CAN FD frame storage. + memset(&sockcan_frame, 0, sizeof sockcan_frame); + struct iovec iov = { + // Scatter/gather array items struct. + .iov_base = &sockcan_frame, // Starting address. + .iov_len = sizeof(sockcan_frame) // Number of bytes to transfer. + + }; + + // Determine the size of the ancillary data and zero-initialize the buffer for it. + // We require space for both the receive message header (implied in CMSG_SPACE) and the time stamp. + // The ancillary data buffer is wrapped in a union to ensure it is suitably aligned. + // See the cmsg(3) man page (release 5.08 dated 2020-06-09, or later) for details. + union + { + uint8_t buf[CMSG_SPACE(sizeof(struct timeval))]; + struct cmsghdr align; + } control; + (void) memset(control.buf, 0, sizeof(control.buf)); + + // Initialize the message header used by recvmsg. + struct msghdr msg; // Message header struct. + memset(&msg, 0, sizeof msg); + msg.msg_iov = &iov; // Scatter/gather array. + msg.msg_iovlen = 1; // Number of elements in the scatter/gather array. + msg.msg_control = control.buf; // Ancillary data. + msg.msg_controllen = sizeof(control.buf); // Ancillary data buffer length. + + // Non-blocking receive messages from the socket and validate. + const ssize_t read_size = recvmsg(fd, &msg, MSG_DONTWAIT); + if (read_size < 0) + { + return getNegatedErrno(); // Error occurred -- return the negated error code. + } + if ((read_size != CAN_MTU) && (read_size != CANFD_MTU)) + { + return -EIO; + } + if (sockcan_frame.len > payload_buffer_size) + { + return -EFBIG; + } + + const bool valid = ((sockcan_frame.can_id & CAN_EFF_FLAG) != 0) && // Extended frame + ((sockcan_frame.can_id & CAN_ERR_FLAG) == 0) && // Not RTR frame + ((sockcan_frame.can_id & CAN_RTR_FLAG) == 0); // Not error frame + if (!valid) + { + return 0; // Not an extended data frame -- drop silently and return early. + } + + // Handle the loopback frame logic. + const bool loopback_frame = ((uint32_t) msg.msg_flags & (uint32_t) MSG_CONFIRM) != 0; + if (loopback == NULL && loopback_frame) + { + return 0; // The loopback pointer is NULL and this is a loopback frame -- drop silently and return early. + } + if (loopback != NULL) + { + *loopback = loopback_frame; + } + + // Obtain the CAN frame time stamp from the kernel. + // This time stamp is from the CLOCK_REALTIME kernel source. + if (NULL != out_timestamp_usec) + { + const struct cmsghdr* cmsg = CMSG_FIRSTHDR(&msg); + struct timeval tv; + memset(&tv, 0, sizeof tv); + assert(cmsg != NULL); + if ((cmsg->cmsg_level == SOL_SOCKET) && (cmsg->cmsg_type == SO_TIMESTAMP)) + { + (void) memcpy(&tv, CMSG_DATA(cmsg), sizeof(tv)); // Copy to avoid alignment problems + assert(tv.tv_sec >= 0 && tv.tv_usec >= 0); + } + else + { + assert(0); + return -EIO; + } + + (void) memset(out_frame, 0, sizeof(struct CanardFrame)); + *out_timestamp_usec = (CanardMicrosecond) (((uint64_t) tv.tv_sec * MEGA) + (uint64_t) tv.tv_usec); + } + out_frame->extended_can_id = sockcan_frame.can_id & CAN_EFF_MASK; + out_frame->payload.size = sockcan_frame.len; + out_frame->payload.data = payload_buffer; + (void) memcpy(payload_buffer, &sockcan_frame.data[0], sockcan_frame.len); + } + return poll_result; +} + +int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const struct CanardFilter* const configs) +{ + if (configs == NULL) + { + return -EINVAL; + } + if (num_configs > CAN_RAW_FILTER_MAX) + { + return -EFBIG; + } + + struct can_filter cfs[CAN_RAW_FILTER_MAX]; + for (size_t i = 0; i < num_configs; i++) + { + cfs[i].can_id = (configs[i].extended_can_id & CAN_EFF_MASK) | CAN_EFF_FLAG; + cfs[i].can_mask = (configs[i].extended_mask & CAN_EFF_MASK) | CAN_EFF_FLAG | CAN_RTR_FLAG; + } + + const int ret = + setsockopt(fd, SOL_CAN_RAW, CAN_RAW_FILTER, cfs, (socklen_t) (sizeof(struct can_filter) * num_configs)); + + return (ret < 0) ? getNegatedErrno() : 0; +} diff --git a/hardware/socketcan.h b/hardware/socketcan.h new file mode 100644 index 0000000..81c75a0 --- /dev/null +++ b/hardware/socketcan.h @@ -0,0 +1,86 @@ +/// ____ ______ __ __ +/// / __ `____ ___ ____ / ____/_ ______ / /_ ____ / / +/// / / / / __ `/ _ `/ __ `/ / / / / / __ `/ __ `/ __ `/ / +/// / /_/ / /_/ / __/ / / / /___/ /_/ / /_/ / / / / /_/ / / +/// `____/ .___/`___/_/ /_/`____/`__, / .___/_/ /_/`__,_/_/ +/// /_/ /____/_/ +/// +/// This is a basic adapter library that bridges Libcanard with SocketCAN. +/// Read the API documentation for usage information. +/// +/// To integrate the library into your application, just copy-paste the c/h files into your project tree. +/// +/// -------------------------------------------------------------------------------------------------------------------- +/// Changelog +/// +/// v3.0 - Update for compatibility with Libcanard v3. +/// +/// v2.0 - Added loop-back functionality. +/// API change in socketcanPop(): loopback flag added. +/// - Changed to kernel-based time-stamping for received frames for improved accuracy. +/// API change in socketcanPop(): time stamp clock source is now CLOCK_REALTIME, vs CLOCK_TAI before. +/// +/// v1.0 - Initial release +/// -------------------------------------------------------------------------------------------------------------------- +/// +/// This software is distributed under the terms of the MIT License. +/// Copyright (c) 2020 OpenCyphal +/// Author: Pavel Kirienko + +#ifndef SOCKETCAN_H_INCLUDED +#define SOCKETCAN_H_INCLUDED + +extern "C" { +#include "canard.h" +#include +#include +#include + +} + +/// File descriptor alias. +typedef int SocketCANFD; + +/// Initialize a new non-blocking (sic!) SocketCAN socket and return its handle on success. +/// On failure, a negated errno is returned. +/// To discard the socket just call close() on it; no additional de-initialization activities are required. +/// The argument can_mtu specifies CAN MTU size: 8 - for classic; >8 (64 normally) - for CAN FD frames. +/// In the future, this MTU size may be extended to support CAN XL. +SocketCANFD socketcanOpen(const char* const iface_name, const size_t can_mtu); + +/// Enqueue a new extended CAN data frame for transmission. +/// Block until the frame is enqueued or until the timeout is expired. +/// Zero timeout makes the operation non-blocking. +/// Returns 1 on success, 0 on timeout, negated errno on error. +int16_t socketcanPush(const SocketCANFD fd, + const struct CanardFrame* const frame, + const CanardMicrosecond timeout_usec); + +/// Fetch a new extended CAN data frame from the RX queue. +/// If the received frame is not an extended-ID data frame, it will be dropped and the function will return early. +/// The payload pointer of the returned frame will point to the payload_buffer. It can be a stack-allocated array. +/// The payload_buffer_size shall be large enough (64 bytes is enough for CAN FD), otherwise an error is returned. +/// The received frame timestamp will be set to CLOCK_REALTIME by the kernel, sampled near the moment of its arrival. +/// The loopback flag pointer is used to both indicate and control behavior when a looped-back message is received. +/// If the flag pointer is NULL, loopback frames are silently dropped; if not NULL, they are accepted and indicated +/// using this flag. +/// The function will block until a frame is received or until the timeout is expired. It may return early. +/// Zero timeout makes the operation non-blocking. +/// Returns 1 on success, 0 on timeout, negated errno on error. +int16_t socketcanPop(const SocketCANFD fd, + struct CanardFrame* const out_frame, + CanardMicrosecond* const out_timestamp_usec, + const size_t payload_buffer_size, + void* const payload_buffer, + const CanardMicrosecond timeout_usec, + bool* const loopback); + +/// Apply the specified acceptance filter configuration. +/// Note that it is only possible to accept extended-format data frames. +/// The default configuration is to accept everything. +/// Returns 0 on success, negated errno on error. +int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const struct CanardFilter* const configs); + + + +#endif diff --git a/lib/libcanard b/lib/libcanard new file mode 160000 index 0000000..962e9c5 --- /dev/null +++ b/lib/libcanard @@ -0,0 +1 @@ +Subproject commit 962e9c5ac9629d761c83d9c6f4f8179faad1e8b0