wip
This commit is contained in:
parent
55524aab6f
commit
df45978fa4
3
.gitmodules
vendored
Normal file
3
.gitmodules
vendored
Normal file
@ -0,0 +1,3 @@
|
||||
[submodule "lib/libcanard"]
|
||||
path = lib/libcanard
|
||||
url = git@git.nilsschulte.de:nils/libcanard.git
|
||||
@ -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
|
||||
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
|
||||
$<INSTALL_INTERFACE:include/cyphal_hardware_interface>
|
||||
${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,
|
||||
|
||||
@ -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"]
|
||||
|
||||
@ -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'),
|
||||
@ -246,8 +231,7 @@ def generate_launch_description():
|
||||
robot_state_pub_node,
|
||||
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
|
||||
#delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
|
||||
] + joy_ld #+ lidar_ld
|
||||
|
||||
return LaunchDescription(declared_arguments + nodes)
|
||||
|
||||
@ -7,9 +7,9 @@
|
||||
<xacro:unless value="${use_mock_hardware}">
|
||||
<hardware>
|
||||
<plugin>cyphal_hardware_interface/cyphalSystemHardware</plugin>
|
||||
<param name="port">/dev/ttyAMA10</param>
|
||||
<param name="can_if">can0</param>
|
||||
<!--param name="port">/dev/ttyACM0</param-->
|
||||
<param name="baud">460800</param>
|
||||
<!--param name="baud">460800</param-->
|
||||
<!--param name="try_next_port_number">false</param-->
|
||||
</hardware>
|
||||
</xacro:unless>
|
||||
@ -19,43 +19,26 @@
|
||||
<param name="calculate_dynamics">true</param>
|
||||
</hardware>
|
||||
</xacro:if>
|
||||
<sensor name="${prefix}driver">
|
||||
<param name="state:battery_voltage">vcc</param>
|
||||
<param name="factor">0.001</param>
|
||||
<state_interface name="battery_voltage"/>
|
||||
</sensor>
|
||||
<joint name="${prefix}vacuum">
|
||||
<param name="command:power">s</param>
|
||||
<param name="factor">0.1427</param>
|
||||
<command_interface name="power">
|
||||
<param name="min">0</param>
|
||||
<param name="max">1</param>
|
||||
</command_interface>
|
||||
</joint>
|
||||
<joint name="${prefix}left_wheel_joint">
|
||||
<param name="command:velocity">vt0</param>
|
||||
<param name="state:position">a0</param>
|
||||
<param name="state:velocity">v0</param>
|
||||
<param name="factor">0.0001</param>
|
||||
<param name="node_id">125</param>
|
||||
<command_interface name="velocity">
|
||||
</command_interface>
|
||||
<state_interface name="position">
|
||||
</state_interface>
|
||||
<!--state_interface name="velocity">
|
||||
</state_interface-->
|
||||
</joint>
|
||||
<joint name="${prefix}right_wheel_joint">
|
||||
<param name="command:velocity">vt1</param>
|
||||
<param name="state:position">a1</param>
|
||||
<param name="state:velocity">v1</param>
|
||||
<param name="factor">0.0001</param>
|
||||
<command_interface name="velocity">
|
||||
</command_interface>
|
||||
<state_interface name="position">
|
||||
<state_interface name="velocity">
|
||||
</state_interface>
|
||||
<state_interface name="acceleration">
|
||||
</state_interface>
|
||||
<!--state_interface name="velocity">
|
||||
</state_interface-->
|
||||
</joint>
|
||||
<!--joint name="${prefix}right_wheel_joint">
|
||||
<param name="nodeid">125</param>
|
||||
<command_interface name="velocity">
|
||||
</command_interface>
|
||||
<state_interface name="position">
|
||||
</state_interface>
|
||||
</joint-->
|
||||
</ros2_control>
|
||||
|
||||
</xacro:macro>
|
||||
|
||||
@ -1,4 +1,6 @@
|
||||
#define NUNAVUT_ASSERT assert
|
||||
#include "cyphal_hardware_interface/cyphal_system.hpp"
|
||||
#include "include/cyphal_hardware_interface/cyphal_system.hpp"
|
||||
|
||||
#include <chrono>
|
||||
#include <cmath>
|
||||
@ -11,49 +13,193 @@
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
//#include "serial.hpp"
|
||||
#include <thread>
|
||||
|
||||
#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 <chrono>
|
||||
#include <cstdint>
|
||||
#include <iomanip> // For std::setw, std::setfill, std::hex, etc.
|
||||
#include <iostream>
|
||||
#include <sstream> // For std::ostringstream
|
||||
#include <thread>
|
||||
|
||||
#define NUNAVUT_ASSERT assert
|
||||
|
||||
extern "C" {
|
||||
#include "canard.h"
|
||||
#include <reg/udral/physics/dynamics/rotation/PlanarTs_0_1.h>
|
||||
#include <reg/udral/service/common/Readiness_0_1.h>
|
||||
#include <uavcan/_register/Access_1_0.h>
|
||||
#include <uavcan/_register/List_1_0.h>
|
||||
#include <uavcan/_register/Value_1_0.h>
|
||||
#include <uavcan/node/Heartbeat_1_0.h>
|
||||
#include <uavcan/node/port/List_0_1.h>
|
||||
}
|
||||
|
||||
namespace cyphal_hardware_interface {
|
||||
|
||||
uint64_t getMonotonicMicroseconds() {
|
||||
auto now = std::chrono::steady_clock::now();
|
||||
auto micros = std::chrono::duration_cast<std::chrono::microseconds>(
|
||||
now.time_since_epoch())
|
||||
.count();
|
||||
return static_cast<uint64_t>(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_readiness(
|
||||
enum arming_state arming_state_target) {
|
||||
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 = 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::write_register(cyphalUdralServo &servo,
|
||||
std::string name,
|
||||
uavcan_register_Value_1_0 value) {
|
||||
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();
|
||||
msg.value = 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);
|
||||
}
|
||||
}
|
||||
|
||||
void cyphalSystemHardware::read_register(cyphalUdralServo &servo,
|
||||
std::string name) {
|
||||
uavcan_register_Value_1_0 value;
|
||||
uavcan_register_Value_1_0_select_empty_(&value);
|
||||
write_register(servo, name, value);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Static method to call read_thread via std::thread
|
||||
* @param context pointer to this
|
||||
*/
|
||||
void cyphalSystemHardware::read_thread_static(void *context) {
|
||||
static_cast<cyphalSystemHardware *>(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<std::string>({"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<hardware_interface::ComponentInfo> components;
|
||||
components.insert(components.begin(), info_.joints.begin(),
|
||||
@ -61,250 +207,423 @@ 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<double>::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<double>::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;
|
||||
servos[node_id].name = joint.name;
|
||||
} 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;
|
||||
}
|
||||
|
||||
static struct CanardRxSubscription rx_reg_udral_physics_dynamics_;
|
||||
res = //
|
||||
canardRxSubscribe(
|
||||
&canard, CanardTransferKindMessage, dynamics_state_port,
|
||||
reg_udral_physics_dynamics_rotation_PlanarTs_0_1_EXTENT_BYTES_,
|
||||
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
|
||||
&rx_reg_udral_physics_dynamics_);
|
||||
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<hardware_interface::StateInterface>
|
||||
cyphalSystemHardware::export_state_interfaces() {
|
||||
std::vector<hardware_interface::StateInterface> 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<hardware_interface::CommandInterface>
|
||||
cyphalSystemHardware::export_command_interfaces() {
|
||||
std::vector<hardware_interface::CommandInterface> 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 + 10s) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("cyphalSystemHardware"),
|
||||
"Timed out while waiting for servos");
|
||||
return hardware_interface::CallbackReturn::ERROR;
|
||||
}
|
||||
std::this_thread::sleep_for(200ms);
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
} else if (transfer->metadata.port_id == dynamics_state_port) {
|
||||
|
||||
if (!servos.contains(node_id)) {
|
||||
return;
|
||||
}
|
||||
|
||||
std::unique_lock lock{servos[node_id].mtx};
|
||||
reg_udral_physics_dynamics_rotation_PlanarTs_0_1 msg;
|
||||
size_t size = transfer->payload.size;
|
||||
if (reg_udral_physics_dynamics_rotation_PlanarTs_0_1_deserialize_(
|
||||
&msg, (uint8_t *)transfer->payload.data, &size) >= 0) {
|
||||
servos[node_id].state.kinematics = msg.value.kinematics;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void cyphalSystemHardware::write_can() {
|
||||
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.
|
||||
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?)
|
||||
}
|
||||
}
|
||||
|
||||
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!");
|
||||
|
||||
int i = 0;
|
||||
for (auto &[id, s] : servos) {
|
||||
std::unique_lock lock{s.mtx};
|
||||
s.arm_target = ARMED;
|
||||
|
||||
uavcan_register_Value_1_0 value;
|
||||
uavcan_register_Value_1_0_select_natural16_(&value);
|
||||
value.natural16.value.elements[0] = readiness_port;
|
||||
value.natural16.value.count = 1;
|
||||
write_register(s, "uavcan.sub.servo.readiness.id", value);
|
||||
|
||||
const uint16_t dynamics_port = dynamics_state_port;
|
||||
uavcan_register_Value_1_0_select_natural16_(&value);
|
||||
value.natural16.value.elements[0] = dynamics_port;
|
||||
value.natural16.value.count = 1;
|
||||
write_register(s, "uavcan.pub.servo.dynamics.id", value);
|
||||
|
||||
i += 1;
|
||||
}
|
||||
|
||||
return hardware_interface::CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
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));
|
||||
RCLCPP_INFO(rclcpp::get_logger("cyphalSystemHardware"),
|
||||
"%.1f seconds left...", hw_stop_sec_ - i);
|
||||
}
|
||||
// END: This part here is for exemplary purposes - Please do not copy to
|
||||
your
|
||||
// production code
|
||||
|
||||
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());
|
||||
// }
|
||||
for (const auto &[name, descr] : joint_state_interfaces_) {
|
||||
if (descr.get_interface_name() == hardware_interface::HW_IF_POSITION) {
|
||||
for (auto &[id, s] : servos) {
|
||||
std::unique_lock lock{s.mtx};
|
||||
if (s.name == descr.get_prefix_name()) {
|
||||
set_state<double>(name, (double)s.state.kinematics.angular_position.radian);
|
||||
break;
|
||||
}
|
||||
}
|
||||
} else if (descr.get_interface_name() ==
|
||||
hardware_interface::HW_IF_VELOCITY) {
|
||||
for (auto &[id, s] : servos) {
|
||||
std::unique_lock lock{s.mtx};
|
||||
if (s.name == descr.get_prefix_name()) {
|
||||
set_state<double>(name,
|
||||
(double)s.state.kinematics.angular_velocity.radian_per_second);
|
||||
break;
|
||||
}
|
||||
}
|
||||
} else if (descr.get_interface_name() ==
|
||||
hardware_interface::HW_IF_ACCELERATION) {
|
||||
for (auto &[id, s] : servos) {
|
||||
std::unique_lock lock{s.mtx};
|
||||
if (s.name == descr.get_prefix_name()) {
|
||||
set_state<double>(
|
||||
name,
|
||||
(double)s.state.kinematics.angular_acceleration.radian_per_second_per_second);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return hardware_interface::return_type::OK;
|
||||
}
|
||||
@ -312,44 +631,11 @@ cyphalSystemHardware::read(const rclcpp::Time & /*time*/,
|
||||
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_readiness(ARMED);
|
||||
return hardware_interface::return_type::OK;
|
||||
}
|
||||
|
||||
|
||||
@ -17,6 +17,7 @@
|
||||
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
@ -33,32 +34,84 @@
|
||||
|
||||
#include "cyphal_hardware_interface/visibility_control.h"
|
||||
|
||||
//#include "cyphal.hpp"
|
||||
extern "C" {
|
||||
#include "canard.h"
|
||||
#include <uavcan/_register/Access_1_0.h>
|
||||
#include <uavcan/_register/List_1_0.h>
|
||||
#include <uavcan/_register/Value_1_0.h>
|
||||
#include <uavcan/node/port/List_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/rotation/Planar_0_1.h>
|
||||
}
|
||||
|
||||
#include <thread>
|
||||
|
||||
#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;
|
||||
std::string name;
|
||||
mutable std::mutex mtx;
|
||||
std::string cookie = "";
|
||||
std::map<std::string, uavcan_register_Value_1_0> registers;
|
||||
struct {
|
||||
bool alive = false;
|
||||
bool register_read = false;
|
||||
std::string requested_register_name;
|
||||
reg_udral_physics_kinematics_rotation_Planar_0_1 kinematics;
|
||||
} 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<hardware_interface::StateInterface>
|
||||
export_state_interfaces() override;
|
||||
export_state_interfaces() override {
|
||||
return {};
|
||||
};
|
||||
|
||||
CYPHAL_HARDWARE_INTERFACE_PUBLIC
|
||||
std::vector<hardware_interface::CommandInterface>
|
||||
export_command_interfaces() override;
|
||||
export_command_interfaces() override {
|
||||
return {};
|
||||
};
|
||||
|
||||
CYPHAL_HARDWARE_INTERFACE_PUBLIC
|
||||
CYPHAL_HARDWARE_INTERFACE_PUBLIC
|
||||
@ -81,17 +134,48 @@ 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;
|
||||
};
|
||||
const uint16_t readiness_port = 10;
|
||||
const uint16_t dynamics_state_port = 100;
|
||||
|
||||
int serial_port_handle;
|
||||
std::map<int, cyphalUdralServo> servos;
|
||||
|
||||
std::map<std::string, struct interface_params> interfaces_map;
|
||||
int can_socket = -1;
|
||||
|
||||
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 write_register(cyphalUdralServo &servo, std::string name,
|
||||
uavcan_register_Value_1_0 value);
|
||||
|
||||
void send_readiness(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
|
||||
|
||||
593
hardware/include/nunavut/support/serialization.h
Normal file
593
hardware/include/nunavut/support/serialization.h
Normal file
@ -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 <string.h>
|
||||
|
||||
#include <float.h>
|
||||
#include <math.h> // For isfinite().
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <assert.h> // 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)" (<assert.h> 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
|
||||
328
hardware/include/reg/udral/physics/acoustics/Note_0_1.h
Normal file
328
hardware/include/reg/udral/physics/acoustics/Note_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/duration/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/frequency/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/power/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/dynamics/rotation/Planar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/rotation/Planar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/torque/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/dynamics/translation/Linear_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/translation/Linear_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/force/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
279
hardware/include/reg/udral/physics/electricity/PowerTs_0_1.h
Normal file
279
hardware/include/reg/udral/physics/electricity/PowerTs_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/electricity/Power_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
279
hardware/include/reg/udral/physics/electricity/Power_0_1.h
Normal file
279
hardware/include/reg/udral/physics/electricity/Power_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/electric_current/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/voltage/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
279
hardware/include/reg/udral/physics/electricity/SourceTs_0_1.h
Normal file
279
hardware/include/reg/udral/physics/electricity/SourceTs_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/electricity/Source_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
327
hardware/include/reg/udral/physics/electricity/Source_0_1.h
Normal file
327
hardware/include/reg/udral/physics/electricity/Source_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/electricity/Power_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/energy/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/PointStateVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/PointVar_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/translation/Velocity3Var_0_2.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Point_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/velocity/Vector3_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Point_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/length/WideVector3_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/PoseVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Pose_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Point_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/angle/Quaternion_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/StateVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/PoseVar_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/TwistVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Pose_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Twist_0_1.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/TwistVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Twist_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/angular_velocity/Vector3_1_0.h>
|
||||
#include <uavcan/si/unit/velocity/Vector3_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/PointStateVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/PointVar_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/translation/Velocity3Var_0_2.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/Point_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/velocity/Vector3_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/Point_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/length/WideScalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/Pose_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/Point_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/angle/Quaternion_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/StateVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/TwistVar_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/PoseVar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/cartesian/Twist_0_1.h>
|
||||
#include <reg/udral/physics/kinematics/geodetic/Pose_0_1.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/rotation/Planar_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/angle/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/angular_acceleration/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/angular_velocity/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/translation/Linear_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/kinematics/translation/LinearTs_0_1.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/acceleration/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/length/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/velocity/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/sample/velocity/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <uavcan/si/sample/velocity/Vector3_1_0.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <uavcan/si/unit/velocity/Vector3_1_0.h>
|
||||
|
||||
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_
|
||||
269
hardware/include/reg/udral/physics/optics/HighColor_0_1.h
Normal file
269
hardware/include/reg/udral/physics/optics/HighColor_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <uavcan/si/unit/pressure/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/temperature/Scalar_1_0.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
279
hardware/include/reg/udral/physics/time/TAI64VarTs_0_1.h
Normal file
279
hardware/include/reg/udral/physics/time/TAI64VarTs_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/time/TAI64Var_0_1.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
249
hardware/include/reg/udral/physics/time/TAI64Var_0_1.h
Normal file
249
hardware/include/reg/udral/physics/time/TAI64Var_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/physics/time/TAI64_0_1.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
213
hardware/include/reg/udral/physics/time/TAI64_0_1.h
Normal file
213
hardware/include/reg/udral/physics/time/TAI64_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/service/common/Heartbeat_0_1.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
347
hardware/include/reg/udral/service/actuator/common/Status_0_1.h
Normal file
347
hardware/include/reg/udral/service/actuator/common/Status_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/service/actuator/common/FaultFlags_0_1.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/temperature/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
|
||||
175
hardware/include/reg/udral/service/actuator/common/_0_1.h
Normal file
175
hardware/include/reg/udral/service/actuator/common/_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
|
||||
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
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_
|
||||
|
||||
171
hardware/include/reg/udral/service/actuator/common/sp/_0_1.h
Normal file
171
hardware/include/reg/udral/service/actuator/common/sp/_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
168
hardware/include/reg/udral/service/actuator/esc/_0_1.h
Normal file
168
hardware/include/reg/udral/service/actuator/esc/_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
168
hardware/include/reg/udral/service/actuator/servo/_0_1.h
Normal file
168
hardware/include/reg/udral/service/actuator/servo/_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
252
hardware/include/reg/udral/service/battery/Error_0_1.h
Normal file
252
hardware/include/reg/udral/service/battery/Error_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
928
hardware/include/reg/udral/service/battery/Parameters_0_3.h
Normal file
928
hardware/include/reg/udral/service/battery/Parameters_0_3.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/service/battery/Technology_0_1.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/electric_charge/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/electric_current/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/mass/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/voltage/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
|
||||
471
hardware/include/reg/udral/service/battery/Status_0_2.h
Normal file
471
hardware/include/reg/udral/service/battery/Status_0_2.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/service/battery/Error_0_1.h>
|
||||
#include <reg/udral/service/common/Heartbeat_0_1.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/electric_charge/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/temperature/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
|
||||
288
hardware/include/reg/udral/service/battery/Technology_0_1.h
Normal file
288
hardware/include/reg/udral/service/battery/Technology_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
168
hardware/include/reg/udral/service/battery/_0_1.h
Normal file
168
hardware/include/reg/udral/service/battery/_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
283
hardware/include/reg/udral/service/common/Heartbeat_0_1.h
Normal file
283
hardware/include/reg/udral/service/common/Heartbeat_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <reg/udral/service/common/Readiness_0_1.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/node/Health_1_0.h>
|
||||
|
||||
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_
|
||||
224
hardware/include/reg/udral/service/common/Readiness_0_1.h
Normal file
224
hardware/include/reg/udral/service/common/Readiness_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
302
hardware/include/reg/udral/service/sensor/Status_0_1.h
Normal file
302
hardware/include/reg/udral/service/sensor/Status_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/si/unit/duration/Scalar_1_0.h>
|
||||
#include <uavcan/si/unit/temperature/Scalar_1_0.h>
|
||||
|
||||
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_
|
||||
|
||||
558
hardware/include/uavcan/_register/Access_1_0.h
Normal file
558
hardware/include/uavcan/_register/Access_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/_register/Name_1_0.h>
|
||||
#include <uavcan/_register/Value_1_0.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
384
hardware/include/uavcan/_register/List_1_0.h
Normal file
384
hardware/include/uavcan/_register/List_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/_register/Name_1_0.h>
|
||||
|
||||
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_
|
||||
257
hardware/include/uavcan/_register/Name_1_0.h
Normal file
257
hardware/include/uavcan/_register/Name_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
1049
hardware/include/uavcan/_register/Value_1_0.h
Normal file
1049
hardware/include/uavcan/_register/Value_1_0.h
Normal file
File diff suppressed because it is too large
Load Diff
352
hardware/include/uavcan/diagnostic/Record_1_0.h
Normal file
352
hardware/include/uavcan/diagnostic/Record_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/diagnostic/Severity_1_0.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
|
||||
343
hardware/include/uavcan/diagnostic/Record_1_1.h
Normal file
343
hardware/include/uavcan/diagnostic/Record_1_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/diagnostic/Severity_1_0.h>
|
||||
#include <uavcan/time/SynchronizedTimestamp_1_0.h>
|
||||
|
||||
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_
|
||||
|
||||
244
hardware/include/uavcan/diagnostic/Severity_1_0.h
Normal file
244
hardware/include/uavcan/diagnostic/Severity_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
243
hardware/include/uavcan/file/Error_1_0.h
Normal file
243
hardware/include/uavcan/file/Error_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
552
hardware/include/uavcan/file/GetInfo_0_1.h
Normal file
552
hardware/include/uavcan/file/GetInfo_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_1_0.h>
|
||||
|
||||
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_
|
||||
543
hardware/include/uavcan/file/GetInfo_0_2.h
Normal file
543
hardware/include/uavcan/file/GetInfo_0_2.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_2_0.h>
|
||||
|
||||
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_
|
||||
474
hardware/include/uavcan/file/List_0_1.h
Normal file
474
hardware/include/uavcan/file/List_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Path_1_0.h>
|
||||
|
||||
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_
|
||||
465
hardware/include/uavcan/file/List_0_2.h
Normal file
465
hardware/include/uavcan/file/List_0_2.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Path_2_0.h>
|
||||
|
||||
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_
|
||||
529
hardware/include/uavcan/file/Modify_1_0.h
Normal file
529
hardware/include/uavcan/file/Modify_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_1_0.h>
|
||||
|
||||
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_
|
||||
520
hardware/include/uavcan/file/Modify_1_1.h
Normal file
520
hardware/include/uavcan/file/Modify_1_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_2_0.h>
|
||||
|
||||
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_
|
||||
272
hardware/include/uavcan/file/Path_1_0.h
Normal file
272
hardware/include/uavcan/file/Path_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
263
hardware/include/uavcan/file/Path_2_0.h
Normal file
263
hardware/include/uavcan/file/Path_2_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
500
hardware/include/uavcan/file/Read_1_0.h
Normal file
500
hardware/include/uavcan/file/Read_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_1_0.h>
|
||||
|
||||
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_
|
||||
483
hardware/include/uavcan/file/Read_1_1.h
Normal file
483
hardware/include/uavcan/file/Read_1_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_2_0.h>
|
||||
#include <uavcan/primitive/Unstructured_1_0.h>
|
||||
|
||||
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_
|
||||
502
hardware/include/uavcan/file/Write_1_0.h
Normal file
502
hardware/include/uavcan/file/Write_1_0.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_1_0.h>
|
||||
|
||||
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_
|
||||
482
hardware/include/uavcan/file/Write_1_1.h
Normal file
482
hardware/include/uavcan/file/Write_1_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <uavcan/file/Error_1_0.h>
|
||||
#include <uavcan/file/Path_2_0.h>
|
||||
#include <uavcan/primitive/Unstructured_1_0.h>
|
||||
|
||||
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_
|
||||
387
hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_1.h
Normal file
387
hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
378
hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_2.h
Normal file
378
hardware/include/uavcan/internet/udp/HandleIncomingPacket_0_2.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
421
hardware/include/uavcan/internet/udp/OutgoingPacket_0_1.h
Normal file
421
hardware/include/uavcan/internet/udp/OutgoingPacket_0_1.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
412
hardware/include/uavcan/internet/udp/OutgoingPacket_0_2.h
Normal file
412
hardware/include/uavcan/internet/udp/OutgoingPacket_0_2.h
Normal file
@ -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 <nunavut/support/serialization.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
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_
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user