From be853eea93c76dd9dbd5c9e729a8fcf3280e6467 Mon Sep 17 00:00:00 2001
From: wittenator <9154515+wittenator@users.noreply.github.com>
Date: Sat, 2 Dec 2023 19:41:01 +0100
Subject: [PATCH] Big push
---
Dockerfile | 14 +
docker-compose.yml | 10 +
.../{dcaiti_config.yml => ft24_config.yml} | 0
.../description/real_robot_control.xacro | 44 +-
.../description/ros2_control.xacro | 2 +-
src/ft24_control/launch/launch_robot.py | 4 +-
src/ft24_control/launch/launch_sim.py | 3 +-
src/ft24_control/package.xml | 16 +-
.../worlds/generated_worlds/AU2_skidpad.sdf | 2 +-
src/ros2_control_can/CMakeLists.txt | 58 +-
src/ros2_control_can/dbc/CAN1-MainFT24.dbc | 1726 +
.../dbc/FS23_DBC_DE_Berlin_TU_Car013.dbc | 93 -
src/ros2_control_can/fake_robot_hardware.xml | 9 -
.../include/can1__main_ft24.h | 51966 ++++++++++++++++
.../include/ros2_control_can/config.h | 13 +-
.../ros2_control_can/ros2_control_can.h | 13 +-
.../include/ros2_control_can/wheel.h | 1 +
src/ros2_control_can/package.xml | 10 +-
src/ros2_control_can/src/can1__main_ft24.cpp | 33719 ++++++++++
src/ros2_control_can/src/fake_robot.cpp | 129 -
src/ros2_control_can/src/ros2_control_can.cpp | 116 +-
start.bash | 59 -
22 files changed, 87620 insertions(+), 387 deletions(-)
create mode 100644 Dockerfile
create mode 100644 docker-compose.yml
rename src/ft24_control/config/{dcaiti_config.yml => ft24_config.yml} (100%)
create mode 100644 src/ros2_control_can/dbc/CAN1-MainFT24.dbc
delete mode 100644 src/ros2_control_can/dbc/FS23_DBC_DE_Berlin_TU_Car013.dbc
delete mode 100644 src/ros2_control_can/fake_robot_hardware.xml
create mode 100644 src/ros2_control_can/include/can1__main_ft24.h
create mode 100644 src/ros2_control_can/src/can1__main_ft24.cpp
delete mode 100644 src/ros2_control_can/src/fake_robot.cpp
delete mode 100755 start.bash
diff --git a/Dockerfile b/Dockerfile
new file mode 100644
index 0000000..f1d05e0
--- /dev/null
+++ b/Dockerfile
@@ -0,0 +1,14 @@
+# build ROS2 Iron src in container and install depenedencies with rosdep
+
+FROM ros:iron
+
+ADD src /root/ros2_ws/src
+
+RUN apt-get update && apt-get install -y \
+ python3-argcomplete \
+ python3-colcon-common-extensions \
+ python3-vcstool \
+ && rm -rf /var/lib/apt/lists/*
+
+CMD ["bash"]
+
diff --git a/docker-compose.yml b/docker-compose.yml
new file mode 100644
index 0000000..f0cdf38
--- /dev/null
+++ b/docker-compose.yml
@@ -0,0 +1,10 @@
+# docker compose file for the ROS2 Iron project
+
+version: '3'
+
+services:
+ ft24:
+ build: .
+ command: bash
+ volumes:
+ - ./src:/root/ros2_ws/src
\ No newline at end of file
diff --git a/src/ft24_control/config/dcaiti_config.yml b/src/ft24_control/config/ft24_config.yml
similarity index 100%
rename from src/ft24_control/config/dcaiti_config.yml
rename to src/ft24_control/config/ft24_config.yml
diff --git a/src/ft24_control/description/real_robot_control.xacro b/src/ft24_control/description/real_robot_control.xacro
index 0122b1d..be6abaa 100644
--- a/src/ft24_control/description/real_robot_control.xacro
+++ b/src/ft24_control/description/real_robot_control.xacro
@@ -3,34 +3,38 @@
ros2_control_can/Ros2ControlCAN
- left_wheel_joint
- right_wheel_joint
- 30
- /dev/ttyUSB0
- 57600
- 1000
+ front_left_steer_joint
+ front_right_steer_joint
+ rear_left_wheel_joint
+ rear_right_wheel_joint
+ vcan0
+ 50
-
-
- -0.5
- 0.5
-
-
+
+
+
-
-
- -0.5
- 0.5
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
-
- $(find ft24_control)/config/dcaiti_config.yml
+
+ $(find ft24_control)/config/ft24_config.yml
\ No newline at end of file
diff --git a/src/ft24_control/description/ros2_control.xacro b/src/ft24_control/description/ros2_control.xacro
index 2ca8827..0678437 100644
--- a/src/ft24_control/description/ros2_control.xacro
+++ b/src/ft24_control/description/ros2_control.xacro
@@ -27,7 +27,7 @@
- $(find ft24_control)/config/dcaiti_config.yml
+ $(find ft24_control)/config/ft24_config.yml
$(find ft24_control)/config/gaz_ros2_ctl_sim.yml
diff --git a/src/ft24_control/launch/launch_robot.py b/src/ft24_control/launch/launch_robot.py
index 78ab06e..5e9a45b 100644
--- a/src/ft24_control/launch/launch_robot.py
+++ b/src/ft24_control/launch/launch_robot.py
@@ -41,7 +41,7 @@ def generate_launch_description():
controller_params = os.path.join(
get_package_share_directory('ft24_control'), # <-- Replace with your package name
'config',
- 'dcaiti_config.yml'
+ 'ft24_config.yml'
)
controller_manager = Node(
@@ -55,7 +55,7 @@ def generate_launch_description():
diff_drive_spawner = Node(
package="controller_manager",
executable="spawner",
- arguments=["diff_cont"],
+ arguments=["ackermann_steering_controller"],
)
joint_broad_spawner = Node(
diff --git a/src/ft24_control/launch/launch_sim.py b/src/ft24_control/launch/launch_sim.py
index 1d5ca5b..cfaaf30 100644
--- a/src/ft24_control/launch/launch_sim.py
+++ b/src/ft24_control/launch/launch_sim.py
@@ -62,7 +62,6 @@ def generate_launch_description():
arguments=[
'/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock',
'/boxes@vision_msgs/msg/Detection2DArray@ignition.msgs.AnnotatedAxisAligned2DBox_V',
- '/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan',
'/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked',
'lidar/imu@sensor_msgs/msg/Imu@gz.msgs.IMU'
],
@@ -135,6 +134,6 @@ def generate_launch_description():
spawn_entity,
delayed_diff_drive_spawner,
delayed_joint_broad_spawner,
- imu_covariance_adder,
+ #imu_covariance_adder,
#ukf_node
])
diff --git a/src/ft24_control/package.xml b/src/ft24_control/package.xml
index 9339508..5a69599 100644
--- a/src/ft24_control/package.xml
+++ b/src/ft24_control/package.xml
@@ -3,9 +3,19 @@
ft24_control
0.0.0
- TODO: Package description
- MY NAME
- TODO: License declaration
+ This package houses all ros2_control related code
+ Tim Korjakow
+ Todo
+
+ ros2_control
+ ros2_controllers
+ ros_gz
+ robot_localization
+ joint_state_publisher
+ twist_mux
+ gz_ros2_control
+ robot_state_publisher
+
ament_cmake
diff --git a/src/ft24_control/worlds/generated_worlds/AU2_skidpad.sdf b/src/ft24_control/worlds/generated_worlds/AU2_skidpad.sdf
index 4580a4e..6fab173 100644
--- a/src/ft24_control/worlds/generated_worlds/AU2_skidpad.sdf
+++ b/src/ft24_control/worlds/generated_worlds/AU2_skidpad.sdf
@@ -1,7 +1,7 @@
-
+
0.005
1.0
diff --git a/src/ros2_control_can/CMakeLists.txt b/src/ros2_control_can/CMakeLists.txt
index 67f7cff..2f0ce28 100644
--- a/src/ros2_control_can/CMakeLists.txt
+++ b/src/ros2_control_can/CMakeLists.txt
@@ -23,16 +23,41 @@ find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(pluginlib REQUIRED)
+set( GENERATED_CAN_HEADER
+ ${CMAKE_CURRENT_SOURCE_DIR}/include/can1__main_ft24.h
+)
+set(
+ GENERATED_CAN_SRC
+ ${CMAKE_CURRENT_SOURCE_DIR}/src/can1__main_ft24.cpp
+)
+add_custom_command(OUTPUT ${GENERATED_CAN_HEADER} ${GENERATED_CAN_SRC}
+ COMMAND python3 -m cantools generate_c_source --prune ${CMAKE_CURRENT_SOURCE_DIR}/dbc/CAN1-MainFT24.dbc
+ COMMAND mv ${CMAKE_CURRENT_SOURCE_DIR}/src/can1__main_ft24.h ${CMAKE_CURRENT_SOURCE_DIR}/include/can1__main_ft24.h
+ COMMAND mv ${CMAKE_CURRENT_SOURCE_DIR}/src/can1__main_ft24.c ${CMAKE_CURRENT_SOURCE_DIR}/src/can1__main_ft24.cpp
+ WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/src"
+ DEPENDS "${CMAKE_CURRENT_SOURCE_DIR}/dbc/CAN1-MainFT24.dbc"
+ PRE_BUILD
+ COMMENT "Generating CAN header files and code from DBC file"
+ VERBATIM
+)
+add_library(
+ ros2_control_can
+ SHARED
+ src/ros2_control_can.cpp
+ src/wheel.cpp
+ ${GENERATED_CAN_HEADER}
+ ${GENERATED_CAN_SRC}
+)
-add_library(ros2_control_can SHARED src/ros2_control_can.cpp src/wheel.cpp )
target_include_directories(
ros2_control_can
PRIVATE
include
)
+
ament_target_dependencies(
ros2_control_can
hardware_interface
@@ -42,41 +67,20 @@ ament_target_dependencies(
pluginlib
)
-pluginlib_export_plugin_description_file(hardware_interface robot_hardware.xml)
-
-
-
-add_library(fake_robot SHARED src/fake_robot.cpp src/wheel.cpp)
-set_property(TARGET fake_robot PROPERTY POSITION_INDEPENDENT_CODE ON)
-
-target_include_directories(
- fake_robot
- PRIVATE
- include
+pluginlib_export_plugin_description_file(
+ hardware_interface
+ robot_hardware.xml
)
-ament_target_dependencies(
- fake_robot
- hardware_interface
- controller_manager
- rclcpp
- rclcpp_lifecycle
- pluginlib
-)
-
-pluginlib_export_plugin_description_file(hardware_interface fake_robot_hardware.xml)
-
-
-
install(
- TARGETS ros2_control_can fake_robot
+ TARGETS ros2_control_can
DESTINATION lib
)
ament_export_libraries(
ros2_control_can
- fake_robot
)
+
ament_export_dependencies(
hardware_interface
controller_manager
diff --git a/src/ros2_control_can/dbc/CAN1-MainFT24.dbc b/src/ros2_control_can/dbc/CAN1-MainFT24.dbc
new file mode 100644
index 0000000..b6edc06
--- /dev/null
+++ b/src/ros2_control_can/dbc/CAN1-MainFT24.dbc
@@ -0,0 +1,1726 @@
+VERSION ""
+
+
+NS_ :
+ NS_DESC_
+ CM_
+ BA_DEF_
+ BA_
+ VAL_
+ CAT_DEF_
+ CAT_
+ FILTER
+ BA_DEF_DEF_
+ EV_DATA_
+ ENVVAR_DATA_
+ SGTYPE_
+ SGTYPE_VAL_
+ BA_DEF_SGTYPE_
+ BA_SGTYPE_
+ SIG_TYPE_REF_
+ VAL_TABLE_
+ SIG_GROUP_
+ SIG_VALTYPE_
+ SIGTYPE_VALTYPE_
+ BO_TX_BU_
+ BA_DEF_REL_
+ BA_REL_
+ BA_DEF_DEF_REL_
+ BU_SG_REL_
+ BU_EV_REL_
+ BU_BO_REL_
+ SG_MUL_VAL_
+
+BS_:
+
+BU_: Jetson SSU TTS_RL TTS_RR TTS_FR TTS_FL Shunt AMS ABX SDCL PDU PDMV XSens STW EPSC
+
+
+BO_ 3221225472 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX
+ SG_ STW_debugMode : 0|1@1+ (1,0) [0|1] "" Vector__XXX
+
+BO_ 1043 ABX_ParamConfirm: 1 Vector__XXX
+ SG_ ABX_ParamConfirm : 0|8@1+ (1,0) [0|255] "" Vector__XXX
+
+BO_ 272 ABX_Hydraulics: 3 Vector__XXX
+ SG_ ABX_Hyd_PB : 12|12@1+ (0.1,0) [0|409.5] "bar" Vector__XXX
+ SG_ ABX_Hyd_PA : 0|12@1+ (0.1,0) [0|409.5] "bar" Vector__XXX
+
+BO_ 225 JetsonTX: 7 Jetson
+ SG_ Jetson_Torque_Ratio : 32|8@1+ (0.00392156862745098,0) [0|1] "" ABX
+ SG_ Jetson_Brake_Ratio : 24|8@1+ (0.00392156862745098,0) [0|1] "" ABX
+ SG_ Jetson_Cones_Actual : 48|8@1+ (1,0) [0|255] "" ABX
+ SG_ Jetson_Cones_All : 40|8@1+ (1,0) [0|255] "" ABX
+ SG_ Jetson_Lap_Count : 4|4@1+ (1,0) [0|15] "" ABX
+ SG_ Jetson_Steering_Angle : 16|8@1- (0.00784313725490196,0) [-1|1] "" ABX
+ SG_ Jetson_Speed_Target : 8|8@1+ (0.2,0) [0|51] "" ABX
+ SG_ Jetson_AS_OK : 1|1@1+ (1,0) [0|1] "Bool" ABX
+ SG_ Jetson_AS_Mission_Complete : 0|1@1+ (1,0) [0|1] "Bool" ABX
+
+BO_ 1536 AMS_Slave0_Log0: 8 AMS
+ SG_ AMS_Slave0_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1537 AMS_Slave0_Log1: 8 AMS
+ SG_ AMS_Slave0_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1538 AMS_Slave0_Log2: 8 AMS
+ SG_ AMS_Slave0_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1539 AMS_Slave0_Log3: 8 AMS
+ SG_ AMS_Slave0_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave0_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1540 AMS_Slave0_Log4: 6 AMS
+ SG_ AMS_Slave0_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave0_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1541 AMS_Slave0_Log5: 8 AMS
+ SG_ AMS_Slave0_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1542 AMS_Slave0_Log6: 8 AMS
+ SG_ AMS_Slave0_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1543 AMS_Slave0_Log7: 8 AMS
+ SG_ AMS_Slave0_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1544 AMS_Slave0_Log8: 8 AMS
+ SG_ AMS_Slave0_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave0_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1552 AMS_Slave1_Log0: 8 AMS
+ SG_ AMS_Slave1_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1553 AMS_Slave1_Log1: 8 AMS
+ SG_ AMS_Slave1_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1554 AMS_Slave1_Log2: 8 AMS
+ SG_ AMS_Slave1_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1555 AMS_Slave1_Log3: 8 AMS
+ SG_ AMS_Slave1_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave1_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1556 AMS_Slave1_Log4: 6 AMS
+ SG_ AMS_Slave1_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave1_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1557 AMS_Slave1_Log5: 8 AMS
+ SG_ AMS_Slave1_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1558 AMS_Slave1_Log6: 8 AMS
+ SG_ AMS_Slave1_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1559 AMS_Slave1_Log7: 8 AMS
+ SG_ AMS_Slave1_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1560 AMS_Slave1_Log8: 8 AMS
+ SG_ AMS_Slave1_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave1_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1568 AMS_Slave2_Log0: 8 AMS
+ SG_ AMS_Slave2_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1569 AMS_Slave2_Log1: 8 AMS
+ SG_ AMS_Slave2_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1570 AMS_Slave2_Log2: 8 AMS
+ SG_ AMS_Slave2_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1571 AMS_Slave2_Log3: 8 AMS
+ SG_ AMS_Slave2_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave2_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1572 AMS_Slave2_Log4: 6 AMS
+ SG_ AMS_Slave2_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave2_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1573 AMS_Slave2_Log5: 8 AMS
+ SG_ AMS_Slave2_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1574 AMS_Slave2_Log6: 8 AMS
+ SG_ AMS_Slave2_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1575 AMS_Slave2_Log7: 8 AMS
+ SG_ AMS_Slave2_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1576 AMS_Slave2_Log8: 8 AMS
+ SG_ AMS_Slave2_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave2_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1584 AMS_Slave3_Log0: 8 AMS
+ SG_ AMS_Slave3_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1585 AMS_Slave3_Log1: 8 AMS
+ SG_ AMS_Slave3_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1586 AMS_Slave3_Log2: 8 AMS
+ SG_ AMS_Slave3_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1587 AMS_Slave3_Log3: 8 AMS
+ SG_ AMS_Slave3_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave3_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1588 AMS_Slave3_Log4: 6 AMS
+ SG_ AMS_Slave3_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave3_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1589 AMS_Slave3_Log5: 8 AMS
+ SG_ AMS_Slave3_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1590 AMS_Slave3_Log6: 8 AMS
+ SG_ AMS_Slave3_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1591 AMS_Slave3_Log7: 8 AMS
+ SG_ AMS_Slave3_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1592 AMS_Slave3_Log8: 8 AMS
+ SG_ AMS_Slave3_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave3_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1600 AMS_Slave4_Log0: 8 AMS
+ SG_ AMS_Slave4_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1601 AMS_Slave4_Log1: 8 AMS
+ SG_ AMS_Slave4_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1602 AMS_Slave4_Log2: 8 AMS
+ SG_ AMS_Slave4_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1603 AMS_Slave4_Log3: 8 AMS
+ SG_ AMS_Slave4_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave4_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1604 AMS_Slave4_Log4: 6 AMS
+ SG_ AMS_Slave4_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave4_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1605 AMS_Slave4_Log5: 8 AMS
+ SG_ AMS_Slave4_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1606 AMS_Slave4_Log6: 8 AMS
+ SG_ AMS_Slave4_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1607 AMS_Slave4_Log7: 8 AMS
+ SG_ AMS_Slave4_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1608 AMS_Slave4_Log8: 8 AMS
+ SG_ AMS_Slave4_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave4_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1616 AMS_Slave5_Log0: 8 AMS
+ SG_ AMS_Slave5_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1617 AMS_Slave5_Log1: 8 AMS
+ SG_ AMS_Slave5_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1618 AMS_Slave5_Log2: 8 AMS
+ SG_ AMS_Slave5_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1619 AMS_Slave5_Log3: 8 AMS
+ SG_ AMS_Slave5_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave5_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1620 AMS_Slave5_Log4: 6 AMS
+ SG_ AMS_Slave5_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave5_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1621 AMS_Slave5_Log5: 8 AMS
+ SG_ AMS_Slave5_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1622 AMS_Slave5_Log6: 8 AMS
+ SG_ AMS_Slave5_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1623 AMS_Slave5_Log7: 8 AMS
+ SG_ AMS_Slave5_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1624 AMS_Slave5_Log8: 8 AMS
+ SG_ AMS_Slave5_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave5_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1632 AMS_Slave6_Log0: 8 AMS
+ SG_ AMS_Slave6_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1633 AMS_Slave6_Log1: 8 AMS
+ SG_ AMS_Slave6_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1634 AMS_Slave6_Log2: 8 AMS
+ SG_ AMS_Slave6_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1635 AMS_Slave6_Log3: 8 AMS
+ SG_ AMS_Slave6_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave6_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1636 AMS_Slave6_Log4: 6 AMS
+ SG_ AMS_Slave6_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave6_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1637 AMS_Slave6_Log5: 8 AMS
+ SG_ AMS_Slave6_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1638 AMS_Slave6_Log6: 8 AMS
+ SG_ AMS_Slave6_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1639 AMS_Slave6_Log7: 8 AMS
+ SG_ AMS_Slave6_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1640 AMS_Slave6_Log8: 8 AMS
+ SG_ AMS_Slave6_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave6_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1648 AMS_Slave7_Log0: 8 AMS
+ SG_ AMS_Slave7_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1649 AMS_Slave7_Log1: 8 AMS
+ SG_ AMS_Slave7_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1650 AMS_Slave7_Log2: 8 AMS
+ SG_ AMS_Slave7_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1651 AMS_Slave7_Log3: 8 AMS
+ SG_ AMS_Slave7_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave7_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1652 AMS_Slave7_Log4: 6 AMS
+ SG_ AMS_Slave7_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave7_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1653 AMS_Slave7_Log5: 8 AMS
+ SG_ AMS_Slave7_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1654 AMS_Slave7_Log6: 8 AMS
+ SG_ AMS_Slave7_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1655 AMS_Slave7_Log7: 8 AMS
+ SG_ AMS_Slave7_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1656 AMS_Slave7_Log8: 8 AMS
+ SG_ AMS_Slave7_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave7_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1664 AMS_Slave8_Log0: 8 AMS
+ SG_ AMS_Slave8_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1665 AMS_Slave8_Log1: 8 AMS
+ SG_ AMS_Slave8_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1666 AMS_Slave8_Log2: 8 AMS
+ SG_ AMS_Slave8_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1667 AMS_Slave8_Log3: 8 AMS
+ SG_ AMS_Slave8_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave8_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1668 AMS_Slave8_Log4: 6 AMS
+ SG_ AMS_Slave8_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave8_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1669 AMS_Slave8_Log5: 8 AMS
+ SG_ AMS_Slave8_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1670 AMS_Slave8_Log6: 8 AMS
+ SG_ AMS_Slave8_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1671 AMS_Slave8_Log7: 8 AMS
+ SG_ AMS_Slave8_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1672 AMS_Slave8_Log8: 8 AMS
+ SG_ AMS_Slave8_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave8_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1680 AMS_Slave9_Log0: 8 AMS
+ SG_ AMS_Slave9_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1681 AMS_Slave9_Log1: 8 AMS
+ SG_ AMS_Slave9_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1682 AMS_Slave9_Log2: 8 AMS
+ SG_ AMS_Slave9_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1683 AMS_Slave9_Log3: 8 AMS
+ SG_ AMS_Slave9_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave9_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1684 AMS_Slave9_Log4: 6 AMS
+ SG_ AMS_Slave9_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave9_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1685 AMS_Slave9_Log5: 8 AMS
+ SG_ AMS_Slave9_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1686 AMS_Slave9_Log6: 8 AMS
+ SG_ AMS_Slave9_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1687 AMS_Slave9_Log7: 8 AMS
+ SG_ AMS_Slave9_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1688 AMS_Slave9_Log8: 8 AMS
+ SG_ AMS_Slave9_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave9_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1696 AMS_Slave10_Log0: 8 AMS
+ SG_ AMS_Slave10_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1697 AMS_Slave10_Log1: 8 AMS
+ SG_ AMS_Slave10_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1698 AMS_Slave10_Log2: 8 AMS
+ SG_ AMS_Slave10_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1699 AMS_Slave10_Log3: 8 AMS
+ SG_ AMS_Slave10_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave10_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1700 AMS_Slave10_Log4: 6 AMS
+ SG_ AMS_Slave10_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave10_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1701 AMS_Slave10_Log5: 8 AMS
+ SG_ AMS_Slave10_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1702 AMS_Slave10_Log6: 8 AMS
+ SG_ AMS_Slave10_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1703 AMS_Slave10_Log7: 8 AMS
+ SG_ AMS_Slave10_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1704 AMS_Slave10_Log8: 8 AMS
+ SG_ AMS_Slave10_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave10_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1712 AMS_Slave11_Log0: 8 AMS
+ SG_ AMS_Slave11_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1713 AMS_Slave11_Log1: 8 AMS
+ SG_ AMS_Slave11_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1714 AMS_Slave11_Log2: 8 AMS
+ SG_ AMS_Slave11_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1715 AMS_Slave11_Log3: 8 AMS
+ SG_ AMS_Slave11_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave11_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1716 AMS_Slave11_Log4: 6 AMS
+ SG_ AMS_Slave11_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave11_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1717 AMS_Slave11_Log5: 8 AMS
+ SG_ AMS_Slave11_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1718 AMS_Slave11_Log6: 8 AMS
+ SG_ AMS_Slave11_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1719 AMS_Slave11_Log7: 8 AMS
+ SG_ AMS_Slave11_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1720 AMS_Slave11_Log8: 8 AMS
+ SG_ AMS_Slave11_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave11_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1728 AMS_Slave12_Log0: 8 AMS
+ SG_ AMS_Slave12_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1729 AMS_Slave12_Log1: 8 AMS
+ SG_ AMS_Slave12_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1730 AMS_Slave12_Log2: 8 AMS
+ SG_ AMS_Slave12_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1731 AMS_Slave12_Log3: 8 AMS
+ SG_ AMS_Slave12_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave12_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1732 AMS_Slave12_Log4: 6 AMS
+ SG_ AMS_Slave12_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave12_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1733 AMS_Slave12_Log5: 8 AMS
+ SG_ AMS_Slave12_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1734 AMS_Slave12_Log6: 8 AMS
+ SG_ AMS_Slave12_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1735 AMS_Slave12_Log7: 8 AMS
+ SG_ AMS_Slave12_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1736 AMS_Slave12_Log8: 8 AMS
+ SG_ AMS_Slave12_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave12_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1744 AMS_Slave13_Log0: 8 AMS
+ SG_ AMS_Slave13_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1745 AMS_Slave13_Log1: 8 AMS
+ SG_ AMS_Slave13_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1746 AMS_Slave13_Log2: 8 AMS
+ SG_ AMS_Slave13_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1747 AMS_Slave13_Log3: 8 AMS
+ SG_ AMS_Slave13_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave13_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1748 AMS_Slave13_Log4: 6 AMS
+ SG_ AMS_Slave13_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave13_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1749 AMS_Slave13_Log5: 8 AMS
+ SG_ AMS_Slave13_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1750 AMS_Slave13_Log6: 8 AMS
+ SG_ AMS_Slave13_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1751 AMS_Slave13_Log7: 8 AMS
+ SG_ AMS_Slave13_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1752 AMS_Slave13_Log8: 8 AMS
+ SG_ AMS_Slave13_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave13_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1760 AMS_Slave14_Log0: 8 AMS
+ SG_ AMS_Slave14_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1761 AMS_Slave14_Log1: 8 AMS
+ SG_ AMS_Slave14_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1762 AMS_Slave14_Log2: 8 AMS
+ SG_ AMS_Slave14_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1763 AMS_Slave14_Log3: 8 AMS
+ SG_ AMS_Slave14_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave14_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1764 AMS_Slave14_Log4: 6 AMS
+ SG_ AMS_Slave14_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave14_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1765 AMS_Slave14_Log5: 8 AMS
+ SG_ AMS_Slave14_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1766 AMS_Slave14_Log6: 8 AMS
+ SG_ AMS_Slave14_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1767 AMS_Slave14_Log7: 8 AMS
+ SG_ AMS_Slave14_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1768 AMS_Slave14_Log8: 8 AMS
+ SG_ AMS_Slave14_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave14_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1776 AMS_Slave15_Log0: 8 AMS
+ SG_ AMS_Slave15_V3 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V2 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V1 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V0 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1777 AMS_Slave15_Log1: 8 AMS
+ SG_ AMS_Slave15_V7 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V6 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V5 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V4 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1778 AMS_Slave15_Log2: 8 AMS
+ SG_ AMS_Slave15_V11 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V10 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V9 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V8 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1779 AMS_Slave15_Log3: 8 AMS
+ SG_ AMS_Slave15_V15 : 55|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V14 : 39|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V13 : 23|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+ SG_ AMS_Slave15_V12 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1780 AMS_Slave15_Log4: 6 AMS
+ SG_ AMS_Slave15_FailedSensors : 23|32@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_Slave15_V16 : 7|16@0+ (0.0001,0) [0|6.5535] "V" Vector__XXX
+
+BO_ 1781 AMS_Slave15_Log5: 8 AMS
+ SG_ AMS_Slave15_T7 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T6 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T5 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T4 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T3 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T2 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T1 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T0 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1782 AMS_Slave15_Log6: 8 AMS
+ SG_ AMS_Slave15_T15 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T14 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T13 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T12 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T11 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T10 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T9 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T8 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1783 AMS_Slave15_Log7: 8 AMS
+ SG_ AMS_Slave15_T23 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T22 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T21 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T20 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T19 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T18 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T17 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T16 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 1784 AMS_Slave15_Log8: 8 AMS
+ SG_ AMS_Slave15_T31 : 56|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T30 : 48|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T29 : 40|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T28 : 32|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T27 : 24|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T26 : 16|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T25 : 8|8@1- (1,0) [-128|127] "degC" Vector__XXX
+ SG_ AMS_Slave15_T24 : 0|8@1- (1,0) [-128|127] "degC" Vector__XXX
+
+BO_ 224 JetsonRX: 4 ABX
+ SG_ Jetson_AllowTorque : 24|1@1+ (1,0) [0|1] "bool" Vector__XXX
+ SG_ Jetson_Reset : 7|1@1+ (1,0) [0|1] "bool" Vector__XXX
+ SG_ Jetson_Power_Off : 6|1@1+ (1,0) [0|1] "bool" Vector__XXX
+ SG_ Jetson_Speed_XSens : 16|8@1+ (0.2,0) [0|51] "m/s" Vector__XXX
+ SG_ Jetson_Speed : 8|8@1+ (0.2,0) [0|51] "m/s" Jetson
+ SG_ Jetson_AS_State : 3|3@1+ (1,0) [0|5] "" Jetson
+ SG_ Jetson_AS_Mission : 0|3@1+ (1,0) [0|7] "int" Jetson
+
+BO_ 143 AMS_Slave15Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 142 AMS_Slave14Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 141 AMS_Slave13Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 140 AMS_Slave12Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 139 AMS_Slave11Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 138 AMS_Slave10Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 137 AMS_Slave9Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 136 AMS_Slave8Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 135 AMS_Slave7Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 134 AMS_Slave6Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 133 AMS_Slave5Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 132 AMS_Slave4Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 131 AMS_Slave3Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 130 AMS_Slave2Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 129 AMS_Slave1Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 265 ABX_Misc: 7 ABX
+ SG_ ABX_LV_Voltage : 48|8@1+ (0.0588235294117647,0) [0|15] "V" Vector__XXX
+ SG_ ABX_LV_SoC : 40|8@1+ (1,0) [0|100] "%" Vector__XXX
+ SG_ ABX_DriverProtocol : 0|3@1+ (1,0) [0|7] "" Vector__XXX
+ SG_ ABX_Distance_total : 24|16@1+ (0.01,0) [0|655.35] "km" Vector__XXX
+ SG_ ABX_Distance_session : 8|16@1+ (1,0) [0|65535] "m" Vector__XXX
+
+BO_ 12 AMS_Error: 2 AMS
+ SG_ AMS_Error_Arg : 8|8@1- (1,0) [0|0] "" ABX
+ SG_ AMS_Error_Kind : 0|8@1- (1,0) [0|0] "" ABX
+
+BO_ 264 ABX_CoolingSys_Internal: 8 ABX
+ SG_ ABX_CS_T_MotR : 48|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+ SG_ ABX_CS_T_MotL : 32|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+ SG_ ABX_CS_T_InvR : 16|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+ SG_ ABX_CS_T_InvL : 0|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+
+BO_ 262 ABX_CoolingSys_Acc: 6 ABX
+ SG_ ABX_CS_T_AccOut : 32|10@1+ (0.1,0) [0|102.3] "�C" Vector__XXX
+ SG_ ABX_CS_T_AccIn : 16|10@1+ (0.1,0) [0|102.3] "�C" Vector__XXX
+ SG_ ABX_CS_P_AccOut : 8|8@1+ (0.02,0) [0|4] "bar" Vector__XXX
+ SG_ ABX_CS_P_AccIn : 0|8@1+ (0.02,0) [0|4] "bar" Vector__XXX
+
+BO_ 263 ABX_CoolingSys_MotInv: 8 ABX
+ SG_ ABX_CS_P_MotRIn : 24|8@1+ (0.02,0) [0|4] "bar" Vector__XXX
+ SG_ ABX_CS_T_RadIn : 52|10@1+ (0.1,0) [0|102.3] "�C" Vector__XXX
+ SG_ ABX_CS_T_MotIn : 42|10@1+ (0.1,0) [0|102.3] "�C" Vector__XXX
+ SG_ ABX_CS_T_InvIn : 32|10@1+ (0.1,0) [0|102.3] "�C" Vector__XXX
+ SG_ ABX_CS_P_RadIn : 16|8@1+ (0.02,0) [0|4] "bar" Vector__XXX
+ SG_ ABX_CS_P_MotLIn : 8|8@1+ (0.02,0) [0|4] "bar" Vector__XXX
+ SG_ ABX_CS_P_InvIn : 0|8@1+ (0.02,0) [0|4] "bar" Vector__XXX
+
+BO_ 261 ABX_BrakeT: 8 ABX
+ SG_ ABX_BrakeT_RR : 48|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+ SG_ ABX_BrakeT_RL : 32|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+ SG_ ABX_BrakeT_FR : 16|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+ SG_ ABX_BrakeT_FL : 0|16@1+ (0.01,0) [0|655.35] "�C" Vector__XXX
+
+BO_ 260 ABX_Wheelspeed: 8 ABX
+ SG_ ABX_Wheelspeed_RR : 48|16@1- (0.001,0) [-32.768|32.767] "1/s" Vector__XXX
+ SG_ ABX_Wheelspeed_RL : 32|16@1- (0.001,0) [-32.768|32.767] "1/s" Vector__XXX
+ SG_ ABX_Wheelspeed_FR : 16|16@1- (0.001,0) [-32.768|32.767] "1/s" Vector__XXX
+ SG_ ABX_Wheelspeed_FL : 0|16@1- (0.001,0) [-32.768|32.767] "1/s" Vector__XXX
+
+BO_ 259 ABX_Dampers: 8 ABX
+ SG_ ABX_DamperRoll_R : 48|16@1+ (0.01,0) [0|75] "mm" Vector__XXX
+ SG_ ABX_DamperRoll_F : 16|16@1+ (0.01,0) [0|75] "mm" Vector__XXX
+ SG_ ABX_DamperHeave_R : 32|16@1+ (0.01,0) [0|75] "mm" Vector__XXX
+ SG_ ABX_DamperHeave_F : 0|16@1+ (0.01,0) [0|75] "mm" Vector__XXX
+
+BO_ 258 ABX_Timings: 8 ABX
+ SG_ ABX_Sectortime_last : 48|16@1+ (0.01,0) [0|655.35] "s" Vector__XXX
+ SG_ ABX_Sectortime_best : 32|16@1+ (0.01,0) [0|655.35] "s" Vector__XXX
+ SG_ ABX_Laptime_last : 16|16@1+ (0.01,0) [0|655.35] "s" Vector__XXX
+ SG_ ABX_Laptime_best : 0|16@1+ (0.01,0) [0|655.35] "s" Vector__XXX
+
+BO_ 257 ABX_Driver: 8 ABX
+ SG_ ABX_Sectorcounter : 56|8@1+ (1,0) [0|255] "" Vector__XXX
+ SG_ ABX_Lapcounter : 48|8@1+ (1,0) [0|255] "" Vector__XXX
+ SG_ ABX_Steering_Angle : 32|8@1- (1,0) [-128|127] "�" Vector__XXX
+ SG_ ABX_Speed : 40|8@1+ (0.2,0) [0|51] "m/s" Vector__XXX
+ SG_ ABX_BrakeP_R : 20|12@1+ (0.1,0) [0|160] "bar" Vector__XXX
+ SG_ ABX_BrakeP_F : 8|12@1+ (0.1,0) [0|160] "bar" Vector__XXX
+ SG_ ABX_APPS_percent : 0|8@1+ (1,0) [0|100] "%" Vector__XXX
+
+BO_ 1792 TTS_Config: 1 ABX
+ SG_ TTS_NewID : 0|2@1+ (1,0) [0|3] "" Vector__XXX
+
+BO_ 1796 TTS_RR: 8 TTS_RR
+ SG_ TTS_RR_Outer : 48|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RR_Inner : 0|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RR_CenterOut : 36|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RR_CenterIn : 12|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RR_Center : 24|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+
+BO_ 1795 TTS_RL: 8 TTS_RL
+ SG_ TTS_RL_Outer : 0|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RL_Inner : 48|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RL_CenterIn : 36|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RL_CenterOut : 12|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_RL_Center : 24|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+
+BO_ 1794 TTS_FR: 8 TTS_FR
+ SG_ TTS_FR_Outer : 48|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FR_Inner : 0|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FR_CenterIn : 12|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FR_CenterOut : 36|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FR_Center : 24|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+
+BO_ 1793 TTS_FL: 8 TTS_FL
+ SG_ TTS_FL_Outer : 0|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FL_Inner : 48|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FL_CenterIn : 36|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FL_CenterOut : 12|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+ SG_ TTS_FL_Center : 24|12@1- (0.1,150) [-54.8|354.7] "�C" Vector__XXX
+
+BO_ 1026 STW_Param_Set: 5 STW
+ SG_ STW_Param_BBal m0 : 15|32@0+ (0.1,0) [0|0] "" Vector__XXX
+ SG_ STW_Param_Type M : 0|8@1+ (1,0) [0|0] "" Vector__XXX
+ SG_ STW_Param_SLIPREF m1 : 15|32@0+ (0.01,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_ASRP m3 : 15|32@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_ASRON m4 : 15|32@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_ASRI m5 : 15|32@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_EnduPowerLimit m6 : 15|32@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_Test3 m7 : 15|32@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_Test4 m8 : 15|32@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ STW_Param_MUMAX m2 : 15|32@0+ (0.1,0) [0|1] "" Vector__XXX
+
+BO_ 128 AMS_Slave0Status: 8 AMS
+ SG_ AMS_SlaveStatus_ID : 6|7@0+ (1,0) [0|0] "" Vector__XXX
+ SG_ AMS_SlaveStatus_Error : 7|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ AMS_SlaveStatus_SoC : 15|8@0+ (1,0) [0|1] "%" Vector__XXX
+ SG_ AMS_SlaveStatus_MinCellVolt : 23|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxCellVolt : 39|16@0+ (0.0001,0) [0|1] "V" Vector__XXX
+ SG_ AMS_SlaveStatus_MaxTemp : 51|12@0- (0.0625,0) [0|1] "degC" Vector__XXX
+
+BO_ 1280 SSU_Message: 4 SSU
+ SG_ SSU_AirTemp : 16|16@1- (0.1,0) [-20|80] "�C" Vector__XXX
+ SG_ SSU_AirPressure : 0|16@1- (1,0) [-1000|1000] "Pa" Vector__XXX
+
+BO_ 10 AMS_Status: 6 AMS
+ SG_ AMS_State : 0|7@1+ (1,0) [0|1] "" ABX
+ SG_ SDC_Closed : 7|1@1+ (1,0) [0|1] "" ABX
+ SG_ SOC : 8|8@1+ (1,0) [0|100] "%" ABX
+ SG_ Min_cell_volt : 23|16@0+ (0.0001,0) [0|5] "V" ABX
+ SG_ Max_cell_temp : 39|16@0+ (0.0625,0) [0|4095.94] "°C" ABX
+
+BO_ 9 AMS_SlavePanic: 8 AMS
+ SG_ AMS_SlavePanic_Kind : 15|8@0+ (1,0) [0|7.20576E+016] "" ABX
+ SG_ AMS_SlavePanic_SlaveID : 0|8@1+ (1,0) [0|255] "" ABX
+ SG_ AMS_SlavePanic_Arg : 23|32@0+ (1,0) [0|7.20576E+016] "" ABX
+
+BO_ 11 AMS_In: 1 ABX
+ SG_ TS_activate : 0|1@1+ (1,0) [0|1] "" AMS
+ SG_ Lap_Number : 2|6@1+ (1,0) [0|64] "Laps" AMS
+ SG_ Inverters_discharged : 1|1@1+ (1,0) [0|1] "" AMS
+
+BO_ 1313 Shunt_Current: 6 Shunt
+ SG_ Shunt_Current : 23|32@0- (0.001,0) [-2000000|2000000] "A" AMS
+
+BO_ 1314 Shunt_Voltage1: 6 Shunt
+ SG_ Shunt_Voltage1 : 23|32@0- (0.001,0) [-2000000|2000000] "V" AMS
+
+BO_ 1315 Shunt_Voltage2: 6 Shunt
+ SG_ Shunt_Voltage2 : 23|32@0- (0.001,0) [-2000000|2000000] "V" AMS
+
+BO_ 1316 Shunt_Voltage3: 6 Shunt
+ SG_ Shunt_Voltage3 : 23|32@0- (0.001,0) [-2000000|2000000] "V" AMS
+
+BO_ 1317 Shunt_Temperature: 6 Shunt
+ SG_ Shunt_Temperature : 23|32@0+ (0.1,0) [0|1000] "°C" ABX
+
+BO_ 16 SDCL_tx: 4 SDCL
+ SG_ asms_state : 0|1@1+ (1,0) [0|1] "" ABX
+ SG_ sdc_state_1 : 1|1@1+ (1,0) [0|1] "" ABX
+ SG_ sdc_state_2 : 2|1@1+ (1,0) [0|1] "" ABX
+ SG_ sdc_state_3 : 3|1@1+ (1,0) [0|1] "" ABX
+ SG_ heartbeat_ok : 4|1@1+ (1,0) [0|1] "" ABX
+ SG_ sdcl_sdc_ready : 5|1@1+ (1,0) [0|1] "" ABX
+ SG_ ts_start_muxed : 6|1@1+ (1,0) [0|1] "" ABX
+ SG_ latch_init_open : 8|1@1+ (1,0) [0|1] "" ABX
+ SG_ latch_closed : 9|1@1+ (1,0) [0|1] "" ABX
+ SG_ latch_reopened : 10|1@1+ (1,0) [0|1] "" ABX
+ SG_ as_mission : 11|3@1+ (1,0) [0|7] "" ABX
+
+BO_ 15 SDCL_rx: 3 ABX
+ SG_ as_close_sdc : 0|1@1+ (1,0) [0|1] "" SDCL
+ SG_ sdcl_heartbeat : 1|1@1+ (1,0) [0|1] "" SDCL
+ SG_ asb_error : 2|1@1+ (1,0) [0|1] "" SDCL
+ SG_ as_mission : 4|3@1+ (1,0) [0|7] "" SDCL
+
+BO_ 200 PDU_Command: 6 ABX
+ SG_ PDU_led3_rx : 13|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ PDU_led2_rx : 14|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ PDU_led1_rx : 15|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ PDU_servo_rx : 1|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_misc_rx : 2|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_alwayson_rx : 3|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_shutdown_circuit_rx : 4|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_ebs_valve_2_rx : 5|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_mode_valve_2_rx : 6|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_inverter_rx : 7|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_mode_valve_1_rx : 8|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_steering_rx : 9|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_ebs_valve_1_rx : 10|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_service_brake_rx : 11|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_sensorbox_rx : 12|1@0+ (1,0) [0|1] "" PDU
+ SG_ PDU_PWM_fans_rx : 23|8@0+ (1,0) [0|255] "" PDU
+ SG_ PDU_PWM_aggregat_rx : 31|8@0+ (1,0) [0|255] "" PDU
+ SG_ PDU_PWM_pump_rx : 39|8@0+ (1,0) [0|255] "" PDU
+ SG_ PDU_checksum_rx : 47|8@0+ (1,0) [0|255] "" PDU
+
+BO_ 201 PDU_Response: 6 PDU
+ SG_ PDU_led3_tx : 13|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ PDU_led2_tx : 14|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ PDU_led1_tx : 15|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ PDU_servo_tx : 1|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_misc_tx : 2|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_alwayson_tx : 3|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_shutdown_circuit_tx : 4|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_evs_valve_2_tx : 5|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_mode_valve_2_tx : 6|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_inverter_tx : 7|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_mode_valve_1_tx : 8|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_steering_tx : 9|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_ebs_valve_1_tx : 10|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_service_brake_tx : 11|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_sensorbox_tx : 12|1@0+ (1,0) [0|1] "" ABX
+ SG_ PDU_PWM_fans_tx : 23|8@0+ (1,0) [0|255] "" ABX
+ SG_ PDU_PWM_aggregat : 31|8@0+ (1,0) [0|255] "" ABX
+ SG_ PDU_PWM_pump : 39|8@0+ (1,0) [0|255] "" ABX
+ SG_ PDU_checksum_tx : 47|8@0+ (1,0) [0|255] "" ABX
+
+BO_ 514 TxPDO: 6 ABX
+ SG_ pdm_output2_shortcircuit : 21|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_output1_shortcircuit : 20|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_output2_cablebreak : 19|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_output1_cablebreak : 18|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_output2_controllerrange : 17|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_output1_controllerrange : 16|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_temperature_shutdown : 13|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_temperature_warning : 12|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_analoginput_currentoverload : 11|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_analoginput_shortcircuit : 10|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_analoginput_cablebreak : 9|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_analoginput_middleposition : 8|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_canbus_statewarning : 5|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_canbus_startupmissing : 4|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_canbus_timeout : 3|1@1+ (1,0) [0|1] "" Vector__XXX
+ SG_ pdm_powersupply_greater_32v : 2|1@1+ (1,0) [0|1] "" ABX
+ SG_ pdm_powersupply_less_8v : 1|1@1+ (1,0) [0|1] "" ABX
+ SG_ PDM_analoginput : 32|16@1+ (1,0) [0|65535] "%." ABX
+
+BO_ 1 XSens_Error: 1 XSens
+
+BO_ 2 XSens_Warning: 1 XSens
+ SG_ WarningCode : 7|8@0+ (1,0) [0|0] "" ABX
+
+BO_ 5 XSens_SampleTime: 4 XSens
+ SG_ Timestamp : 7|32@0+ (1,0) [0|0] "us" ABX
+
+BO_ 6 XSens_GroupCounter: 2 XSens
+ SG_ Counter : 7|16@0+ (1,0) [0|0] "" ABX
+
+BO_ 17 XSens_StatusWord: 4 XSens
+ SG_ SelfTestOk : 24|1@1+ (1,0) [0|1] "" ABX
+ SG_ OrientationValid : 25|1@1+ (1,0) [0|1] "" ABX
+ SG_ GpsValid : 26|1@1+ (1,0) [0|1] "" ABX
+ SG_ NoRotation : 28|2@0+ (1,0) [0|3] "" ABX
+ SG_ RepresentativeMotion : 29|1@1+ (1,0) [0|1] "" ABX
+ SG_ ExternalClockSynced : 30|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipAccX : 16|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipAccY : 17|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipAccZ : 18|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipGyrX : 19|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipGyrY : 20|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipGyrZ : 21|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipMagX : 22|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipMagY : 23|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClipMagZ : 8|1@1+ (1,0) [0|1] "" ABX
+ SG_ Retransmitted : 10|1@1+ (1,0) [0|1] "" ABX
+ SG_ ClippingDetected : 11|1@1+ (1,0) [0|1] "" ABX
+ SG_ Interpolated : 12|1@1+ (1,0) [0|1] "" ABX
+ SG_ SyncIn : 13|1@1+ (1,0) [0|1] "" ABX
+ SG_ SyncOut : 14|1@1+ (1,0) [0|1] "" ABX
+ SG_ FilterMode : 1|3@0+ (1,0) [0|1] "" ABX
+ SG_ HaveGnssTimePulse : 2|1@1+ (1,0) [0|1] "" ABX
+ SG_ RtkStatus : 4|2@0+ (1,0) [0|1] "" ABX
+
+BO_ 50 XSens_RateOfTurn: 6 XSens
+ SG_ XSens_gyrX : 7|16@0- (0.00195313,0) [-35|35] "rad/s" ABX
+ SG_ XSens_gyrY : 23|16@0- (0.00195313,0) [-35|35] "rad/s" ABX
+ SG_ XSens_gyrZ : 39|16@0- (0.00195313,0) [-35|35] "rad/s" ABX
+
+BO_ 52 XSens_Acceleration: 6 XSens
+ SG_ XSens_accX : 7|16@0- (0.00390625,0) [-100|100] "m/s²" ABX
+ SG_ XSens_accY : 23|16@0- (0.00390625,0) [-100|100] "m/s²" ABX
+ SG_ XSens_accZ : 39|16@0- (0.00390625,0) [-100|100] "m/s²" ABX
+
+BO_ 113 XSens_LongLat: 8 XSens
+ SG_ latitude : 7|32@0- (5.96046E-008,0) [-90|90] "deg" ABX
+ SG_ longitude : 39|32@0- (1.19209E-007,0) [-180|180] "deg" ABX
+
+BO_ 118 XSens_Velocity: 6 XSens
+ SG_ velX : 7|16@0- (0.015625,0) [-500|500] "m/s" ABX
+ SG_ velY : 23|16@0- (0.015625,0) [-500|500] "m/s" ABX
+ SG_ velZ : 39|16@0- (0.015625,0) [-500|500] "m/s" ABX
+
+BO_ 1040 AS_Mission_fb: 1 ABX
+ SG_ Mission_selection : 0|3@1+ (1,0) [1|7] "" STW
+
+BO_ 1024 STW_mission_selected: 1 STW
+ SG_ Mission_selection : 0|3@1+ (1,0) [1|7] "" ABX
+
+BO_ 801 EPSC_out: 8 EPSC
+ SG_ EPSC_measured_steering_angle : 7|16@0- (7.20721E-005,0) [-13875|13875] "part of full steering" ABX
+ SG_ EPSC_measured_rpm : 39|12@0- (0.1,0) [-204.8|204.7] "rpm" ABX
+ SG_ EPSC_measured_current : 23|8@0+ (0.1,0) [0|25.5] "A" ABX
+ SG_ EPSC_measured_voltage : 31|8@0+ (0.1,0) [0|20] "V" ABX
+ SG_ EPSC_measured_temperature : 43|10@0+ (0.1,0) [0|102.3] "°C" ABX
+ SG_ EPSC_measured_internal_temp : 49|10@0+ (0.1,0) [0|102.3] "°C" ABX
+
+BO_ 291 EPSC_Steering_In: 2 ABX
+ SG_ EPSC_desired_steering_angle : 7|16@0- (0.0001,0) [-10000|10000] "" EPSC
+
+BO_ 1025 STW_buttons: 1 STW
+ SG_ STW_button_left : 0|1@1+ (1,0) [0|1] "" ABX
+ SG_ STW_button_right : 1|1@1+ (1,0) [0|1] "" ABX
+ SG_ STW_button_R2D : 2|1@1+ (1,0) [0|1] "" ABX
+ SG_ STW_button_Enter : 3|1@1+ (1,0) [0|1] "" ABX
+
+BO_ 1042 STW_status: 6 ABX
+ SG_ InvL_ready : 8|1@1+ (1,0) [0|0] "" STW
+ SG_ iniChk_state : 24|8@1+ (1,0) [0|255] "" STW
+ SG_ InvR_ready : 9|1@1+ (1,0) [0|0] "" STW
+ SG_ AS_State_STW : 0|3@1+ (1,0) [0|5] "" Vector__XXX
+ SG_ SDC_BFL : 10|1@1+ (1,0) [0|0] "" STW
+ SG_ SDC_BRL : 11|1@1+ (1,0) [0|0] "" STW
+ SG_ SDC_ACC : 12|1@1+ (1,0) [0|0] "" STW
+ SG_ SDC_HVB : 13|1@1+ (1,0) [0|0] "" STW
+ SG_ Lap_Count : 16|6@1+ (1,0) [0|64] "" STW
+ SG_ ERR_SDC : 32|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_AMS : 33|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_InvL : 43|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_InvR : 44|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_IniChk : 35|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_ConMon : 36|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_SCS : 37|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_sBSPD : 38|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_APPSp : 39|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_AS : 40|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_ROS : 41|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_RES : 42|1@1+ (1,0) [0|1] "" STW
+ SG_ ERR_PDU : 34|1@1+ (1,0) [0|1] "" STW
+ SG_ R2D_Progress : 4|4@1+ (1,0) [0|15] "" STW
+
+BO_ 202 PDU_Current_1: 8 PDU
+ SG_ PDU_alwayson_curr : 7|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_misc_curr : 23|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_inverter_curr : 39|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_shutdown_circuit_curr : 55|16@0+ (1,0) [0|65535] "" ABX
+
+BO_ 203 PDU_Current_2: 8 PDU
+ SG_ PDU_fans_curr : 7|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_pump_curr : 23|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_aggregat_curr : 39|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_steering_curr : 55|16@0+ (1,0) [0|65535] "" ABX
+
+BO_ 204 PDU_Current_3: 8 PDU
+ SG_ PDU_ebs_valve_1_curr : 7|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_ebs_valve_2_curr : 23|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_mode_valve_1_curr : 39|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_mode_valve_2_curr : 55|16@0+ (1,0) [0|65535] "" ABX
+
+BO_ 205 PDU_Current_4: 8 PDU
+ SG_ PDU_sensorbox_curr : 7|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_service_brake_curr : 23|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_servos_curr : 39|16@0+ (1,0) [0|65535] "" ABX
+ SG_ PDU_shutdown_circuit_curr : 55|16@0+ (1,0) [0|65535] "" ABX
+
+BO_ 292 EPSC_Config_In: 7 ABX
+ SG_ EPSC_Ki_curr m1 : 55|8@0+ (0.1,0) [0|25.6] "" Vector__XXX
+ SG_ EPSC_Kp_curr m1 : 47|8@0+ (0.1,0) [0|25.6] "" Vector__XXX
+ SG_ EPSC_Ki_rpm m1 : 39|8@0+ (0.1,0) [0|25.6] "" Vector__XXX
+ SG_ EPSC_Kp_rpm m1 : 31|8@0+ (0.1,0) [0|25.6] "" Vector__XXX
+ SG_ EPSC_Ki_pos m1 : 23|8@0+ (0.1,0) [0|25.6] "" Vector__XXX
+ SG_ EPSC_Kp_pos m1 : 15|8@0+ (0.1,0) [0|25.6] "" Vector__XXX
+ SG_ EPSC_should_calibrate : 7|1@0- (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_should_change_mode M : 6|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_mode m1 : 5|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_flag3 : 4|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_flag4 : 3|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_flag5 : 2|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_flag6 : 1|1@0+ (1,0) [0|1] "" Vector__XXX
+ SG_ EPSC_flag7 : 0|1@0+ (1,0) [0|1] "" Vector__XXX
+
+
+
+CM_ BU_ XSens "Generic Xsens Motion Sensor";
+CM_ BO_ 3221225472 "This is a message for not used signals, created by Vector CANdb++ DBC OLE DB Provider.";
+CM_ BO_ 225 "Cycle Time: 100ms";
+CM_ BO_ 224 "Cycle Time: 50ms";
+CM_ SG_ 224 Jetson_AS_Mission "AS Mission Selection";
+CM_ BO_ 265 "Cycle time: 1s";
+CM_ BO_ 264 "Cycle time: 100ms";
+CM_ BO_ 262 "Cycle time: 100ms";
+CM_ BO_ 263 "Cycle time: 100ms";
+CM_ BO_ 261 "Cycle time: 100ms";
+CM_ BO_ 260 "Cycle time: 10ms";
+CM_ BO_ 259 "Cycle time: 10ms";
+CM_ BO_ 258 "Cycle time: 1s";
+CM_ BO_ 257 "Cycle time: 10ms";
+CM_ BO_ 1792 "Sent only if TTS positions swapped";
+CM_ SG_ 17 SelfTestOk "Set when the self test result was ok";
+CM_ SG_ 17 OrientationValid "Set when the computed orientation is valid. The orientation may be invalid during startup or when the XSens data is clipping during violent (for the device) motion";
+CM_ SG_ 17 GpsValid "Set when the device has a GPS receiver and the receiver says that there is a GPS position fix.";
+CM_ SG_ 17 RepresentativeMotion "Indicates if the In-Run Compass Calibration is doing the representative motion analysis";
+CM_ SG_ 17 ExternalClockSynced "Indicates whether the internal clock is synced with an external clock (Either GNNS or custom provided clock sync)";
+CM_ SG_ 17 ClipAccX "Indicates if there was clipping on the X-axis of the accelerometer";
+CM_ SG_ 17 ClipAccY "Indicates if there was clipping on the Y-axis of the accelerometer";
+CM_ SG_ 17 ClipAccZ "Indicates if there was clipping on the Z-axis of the accelerometer";
+CM_ SG_ 17 ClipGyrX "Indicates if there was clipping on the X-axis of the gyroscope";
+CM_ SG_ 17 ClipGyrY "Indicates if there was clipping on the Y-axis of the gyroscope";
+CM_ SG_ 17 ClipGyrZ "Indicates if there was clipping on the Z-axis of the gyroscope";
+CM_ SG_ 17 ClipMagX "Indicates if there was clipping on the X-axis of the magnetometer";
+CM_ SG_ 17 ClipMagY "Indicates if there was clipping on the Y-axis of the magnetometer";
+CM_ SG_ 17 ClipMagZ "Indicates if there was clipping on the Z-axis of the magnetometer";
+CM_ SG_ 17 Retransmitted "When set Indicates the sample was received as a retransmission";
+CM_ SG_ 17 ClippingDetected "When set Indicates clipping has occurred";
+CM_ SG_ 17 Interpolated "When set Indicates the sample is an interpolation between other samples";
+CM_ SG_ 17 SyncIn "When set indicates a sync-in event has been triggered";
+CM_ SG_ 17 SyncOut "When set Indicates a sync-out event has been generated";
+CM_ SG_ 17 FilterMode "Mask for the 3 bit filter mode field";
+CM_ SG_ 17 HaveGnssTimePulse "Indicates that the 1PPS GNSS time pulse is present";
+CM_ SG_ 17 RtkStatus "Mask for 2 bit RTK status field";
+CM_ SG_ 801 EPSC_measured_steering_angle "+-13875 equals to +-1.0, so the factor is 1/13875";
+VAL_ 12 AMS_Error_Kind 5 "Shunt Overtemperature" 4 "Shunt Overcurrent" 3 "Shunt Timeout" 2 "Slave Panic" 1 "Slave Timeout" 0 "None" ;
+VAL_ 1026 STW_Param_Type 0 "BrakeBalance" 1 "TractionControl1" 2 "TractionControl2" 3 "TorqueMap" 4 "Test1" 5 "Test2" 6 "Test3" 7 "Test4" ;
+VAL_ 1026 STW_Param_ASRON 0 "OFF" 1 "ON" ;
+VAL_ 10 AMS_State 0 "TS_INACTIVE" 1 "TS_ACTIVE" 2 "TS_PRECHARGE" 3 "TS_DISCHARGE" 4 "TS_ERROR" ;
+VAL_ 9 AMS_SlavePanic_Kind 0 "Overtemperature" 1 "Undertemperature" 2 "Overvoltage" 3 "Undervoltage" 4 "Too_few_working_temperature_sensors" 5 "Open_cell_connection" ;
+VAL_ 17 SelfTestOk 0 "false" 1 "true" ;
+VAL_ 17 OrientationValid 0 "false" 1 "true" ;
+VAL_ 17 GpsValid 0 "false" 1 "true" ;
+VAL_ 17 NoRotation 1 "Aborted" 2 "SamplesRejected" 3 "RunningNormally" ;
+VAL_ 17 RepresentativeMotion 0 "false" 1 "true" ;
+VAL_ 17 ExternalClockSynced 0 "false" 1 "true" ;
+VAL_ 17 ClipAccX 0 "false" 1 "true" ;
+VAL_ 17 ClipAccY 0 "false" 1 "true" ;
+VAL_ 17 ClipAccZ 0 "false" 1 "true" ;
+VAL_ 17 ClipGyrX 0 "false" 1 "true" ;
+VAL_ 17 ClipGyrY 0 "false" 1 "true" ;
+VAL_ 17 ClipGyrZ 0 "false" 1 "true" ;
+VAL_ 17 ClipMagX 0 "false" 1 "true" ;
+VAL_ 17 ClipMagY 0 "false" 1 "true" ;
+VAL_ 17 ClipMagZ 0 "false" 1 "true" ;
+VAL_ 17 Retransmitted 0 "false" 1 "true" ;
+VAL_ 17 ClippingDetected 0 "false" 1 "true" ;
+VAL_ 17 Interpolated 0 "false" 1 "true" ;
+VAL_ 17 SyncIn 0 "false" 1 "true" ;
+VAL_ 17 SyncOut 0 "false" 1 "true" ;
+VAL_ 17 FilterMode 0 "false" 1 "true" ;
+VAL_ 17 HaveGnssTimePulse 0 "false" 1 "true" ;
+VAL_ 17 RtkStatus 0 "No RTK" 1 "RTK floating" 2 "RTK fixed" ;
+VAL_ 1040 Mission_selection 1 "MissionSelection_acceleration" 2 "MissionSelection_skidpad" 3 "MissionSelection_trackdrive" 4 "MissionSelection_braketest" 5 "MissionSelection_inspection" 6 "MissionSelection_autocross" 7 "MissionSelection_manual" ;
+VAL_ 1024 Mission_selection 1 "MissionSelection_acceleration" 2 "MissionSelection_skidpad" 3 "MissionSelection_trackdrive" 4 "MissionSelection_braketest" 5 "MissionSelection_inspection" 6 "MissionSelection_autocross" 7 "MissionSelection_manual" ;
+VAL_ 1042 iniChk_state 0 "Start" 1 "WD_Check" 2 "WD_OK" 3 "ASB_Check_1" 4 "ASB_Check_2" 5 "Wait_TS" 6 "EBS_Check_A" 7 "EBS_Check_B" 8 "Done" 9 "Error" ;
+VAL_ 1042 AS_State_STW 0 "AS_Off" 1 "AS_Manual" 2 "AS_Ready" 3 "AS_Driving" 4 "AS_Finished" 5 "AS_Emergency" ;
+VAL_ 1042 R2D_Progress 0 "R2D_None" 1 "R2D_TSMS" 2 "R2D_TSActive" 3 "R2D_Resetting_Nodes" 4 "R2D_Resetting_Comms" 5 "R2D_Waiting_Init" 6 "R2D_Init_Stage1" 7 "R2D_Init_Stage2" 15 "R2D_Init_Success" ;
+
diff --git a/src/ros2_control_can/dbc/FS23_DBC_DE_Berlin_TU_Car013.dbc b/src/ros2_control_can/dbc/FS23_DBC_DE_Berlin_TU_Car013.dbc
deleted file mode 100644
index 200cc10..0000000
--- a/src/ros2_control_can/dbc/FS23_DBC_DE_Berlin_TU_Car013.dbc
+++ /dev/null
@@ -1,93 +0,0 @@
-VERSION ""
-
-
-NS_ :
- NS_DESC_
- CM_
- BA_DEF_
- BA_
- VAL_
- CAT_DEF_
- CAT_
- FILTER
- BA_DEF_DEF_
- EV_DATA_
- ENVVAR_DATA_
- SGTYPE_
- SGTYPE_VAL_
- BA_DEF_SGTYPE_
- BA_SGTYPE_
- SIG_TYPE_REF_
- VAL_TABLE_
- SIG_GROUP_
- SIG_VALTYPE_
- SIGTYPE_VALTYPE_
- BO_TX_BU_
- BA_DEF_REL_
- BA_REL_
- BA_DEF_DEF_REL_
- BU_SG_REL_
- BU_EV_REL_
- BU_BO_REL_
- SG_MUL_VAL_
-
-BS_:
-
-BU_: ABX RES FS_Datalogger
-
-
-BO_ 1072 FS_Datalogger_Status: 6 FS_Datalogger
- SG_ Current : 32|16@1+ (64,0) [0|4194240] "mA" ABX
- SG_ Voltage : 16|16@1+ (16,0) [0|1048560] "mV" ABX
- SG_ Status_Triggered_Current : 11|1@1- (1,0) [0|0] "" ABX
- SG_ Status_Triggered_Voltage : 10|1@1- (1,0) [0|0] "" ABX
- SG_ Status_Logging : 9|1@1- (1,0) [0|0] "" ABX
- SG_ Status_Ready : 8|1@1- (1,0) [0|0] "" ABX
- SG_ MsgCnt : 0|8@1+ (1,0) [0|255] "" ABX
-
-BO_ 1298 DV_ContinuousMonitoring: 1 ABX
- SG_ Pressure_charged : 5|1@1+ (1,0) [0|1] "bool" FS_Datalogger
- SG_ PDU_comm_alive : 2|1@1+ (1,0) [0|1] "bool" FS_Datalogger
- SG_ Position_sensors_closed : 4|1@1+ (1,0) [0|1] "bool" FS_Datalogger
- SG_ AS_error : 3|1@1+ (1,0) [0|1] "bool" FS_Datalogger
- SG_ AS_comm_alive : 1|1@1+ (1,0) [0|1] "bool" FS_Datalogger
- SG_ SDC_opened : 0|1@1+ (1,0) [0|1] "bool" FS_Datalogger
-
-BO_ 1280 DV_driving_dynamics_1: 8 ABX
- SG_ Speed_actual : 0|8@1+ (1,0) [0|250] "km/h" FS_Datalogger
- SG_ Speed_target : 8|8@1+ (1,0) [0|250] "km/h" FS_Datalogger
- SG_ Steering_angle_actual : 16|8@1- (0.5,0) [-60|60] "°" FS_Datalogger
- SG_ Steering_angle_target : 24|8@1- (0.5,0) [-60|60] "°" FS_Datalogger
- SG_ Brake_hydr_actual : 32|8@1+ (1,0) [0|100] "%" FS_Datalogger
- SG_ Brake_hydr_target : 40|8@1+ (1,0) [0|100] "%" FS_Datalogger
- SG_ Motor_moment_actual : 48|8@1- (1,0) [-100|100] "%" FS_Datalogger
- SG_ Motor_moment_target : 56|8@1- (1,0) [-100|100] "%" FS_Datalogger
-
-BO_ 1281 DV_driving_dynamics_2: 6 ABX
- SG_ Acceleration_longitudinal : 0|16@1- (0.00195313,0) [-50|50] "m/s^2" FS_Datalogger
- SG_ Acceleration_lateral : 16|16@1- (0.00195313,0) [-50|50] "m/s^2" FS_Datalogger
- SG_ Yaw_rate : 32|16@1- (0.0078125,0) [-200|200] "°/s" FS_Datalogger
-
-BO_ 1282 DV_system_status: 5 ABX
- SG_ AS_state : 0|3@1+ (1,0) [1|5] "" FS_Datalogger
- SG_ EBS_state : 3|2@1+ (1,0) [1|3] "" FS_Datalogger
- SG_ AMI_state : 5|3@1+ (1,0) [1|6] "" FS_Datalogger
- SG_ Steering_state : 8|1@1+ (1,0) [0|1] "" FS_Datalogger
- SG_ Service_brake_state : 9|2@1+ (1,0) [1|3] "" FS_Datalogger
- SG_ Lap_counter : 11|4@1+ (1,0) [0|10] "" FS_Datalogger
- SG_ Cones_count_actual : 15|8@1+ (1,0) [0|250] "" FS_Datalogger
- SG_ Cones_count_all : 23|17@1+ (1,0) [0|131000] "" FS_Datalogger
-
-BO_ 1297 DV_SEBSS_Pressures: 8 ABX
- SG_ EBS_Pressure_tank_A : 0|16@1+ (0.1,0) [0|50] "Bar" FS_Datalogger
- SG_ EBS_Pressure_tank_B : 16|16@1+ (0.1,0) [0|50] "Bar" FS_Datalogger
- SG_ Brake_Pressure_front : 32|16@1+ (0.1,0) [0|200] "Bar" FS_Datalogger
- SG_ Brake_Pressure_rear : 48|16@1+ (0.1,0) [0|200] "Bar" FS_Datalogger
-
-
-
-VAL_ 1282 AS_state 1 "AS_state_off" 2 "AS_state_ready" 3 "AS_state_driving" 4 "AS_state_emergency_brake" 5 "AS_state_finish" ;
-VAL_ 1282 EBS_state 1 "EBS_state_unavailable" 2 "EBS_state_armed" 3 "EBS_state_activated" ;
-VAL_ 1282 AMI_state 1 "AMI_state_acceleration" 2 "AMI_state_skidpad" 3 "AMI_state_trackdrive" 4 "AMI_state_braketest" 5 "AMI_state_inspection" 6 "AMI_state_autocross" ;
-VAL_ 1282 Service_brake_state 1 "Service_brake_state_disengaged" 2 "Service_brake_state_engaged" 3 "Service_brake_state_available" ;
-
diff --git a/src/ros2_control_can/fake_robot_hardware.xml b/src/ros2_control_can/fake_robot_hardware.xml
deleted file mode 100644
index e0ae050..0000000
--- a/src/ros2_control_can/fake_robot_hardware.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
- The ROS2 Control minimal robot protocol. This is example for start porting the robot from ROS 1.
-
-
-
diff --git a/src/ros2_control_can/include/can1__main_ft24.h b/src/ros2_control_can/include/can1__main_ft24.h
new file mode 100644
index 0000000..19e961a
--- /dev/null
+++ b/src/ros2_control_can/include/can1__main_ft24.h
@@ -0,0 +1,51966 @@
+/**
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Erik Moqvist
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+/**
+ * This file was generated by cantools version 39.3.0 Mon Nov 27 15:11:10 2023.
+ */
+
+#ifndef CAN1__MAIN_FT24_H
+#define CAN1__MAIN_FT24_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+#include
+#include
+
+#ifndef EINVAL
+# define EINVAL 22
+#endif
+
+/* Frame ids. */
+#define CAN1__MAIN_FT24_ABX_PARAM_CONFIRM_FRAME_ID (0x413u)
+#define CAN1__MAIN_FT24_ABX_HYDRAULICS_FRAME_ID (0x110u)
+#define CAN1__MAIN_FT24_JETSON_TX_FRAME_ID (0xe1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_FRAME_ID (0x600u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_FRAME_ID (0x601u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_FRAME_ID (0x602u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_FRAME_ID (0x603u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG4_FRAME_ID (0x604u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_FRAME_ID (0x605u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_FRAME_ID (0x606u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_FRAME_ID (0x607u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_FRAME_ID (0x608u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_FRAME_ID (0x610u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_FRAME_ID (0x611u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_FRAME_ID (0x612u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_FRAME_ID (0x613u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG4_FRAME_ID (0x614u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_FRAME_ID (0x615u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_FRAME_ID (0x616u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_FRAME_ID (0x617u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_FRAME_ID (0x618u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_FRAME_ID (0x620u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_FRAME_ID (0x621u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_FRAME_ID (0x622u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_FRAME_ID (0x623u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG4_FRAME_ID (0x624u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_FRAME_ID (0x625u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_FRAME_ID (0x626u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_FRAME_ID (0x627u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_FRAME_ID (0x628u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_FRAME_ID (0x630u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_FRAME_ID (0x631u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_FRAME_ID (0x632u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_FRAME_ID (0x633u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG4_FRAME_ID (0x634u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_FRAME_ID (0x635u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_FRAME_ID (0x636u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_FRAME_ID (0x637u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_FRAME_ID (0x638u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_FRAME_ID (0x640u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_FRAME_ID (0x641u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_FRAME_ID (0x642u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_FRAME_ID (0x643u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG4_FRAME_ID (0x644u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_FRAME_ID (0x645u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_FRAME_ID (0x646u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_FRAME_ID (0x647u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_FRAME_ID (0x648u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_FRAME_ID (0x650u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_FRAME_ID (0x651u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_FRAME_ID (0x652u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_FRAME_ID (0x653u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG4_FRAME_ID (0x654u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_FRAME_ID (0x655u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_FRAME_ID (0x656u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_FRAME_ID (0x657u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_FRAME_ID (0x658u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_FRAME_ID (0x660u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_FRAME_ID (0x661u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_FRAME_ID (0x662u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_FRAME_ID (0x663u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG4_FRAME_ID (0x664u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_FRAME_ID (0x665u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_FRAME_ID (0x666u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_FRAME_ID (0x667u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_FRAME_ID (0x668u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_FRAME_ID (0x670u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_FRAME_ID (0x671u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_FRAME_ID (0x672u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_FRAME_ID (0x673u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG4_FRAME_ID (0x674u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_FRAME_ID (0x675u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_FRAME_ID (0x676u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_FRAME_ID (0x677u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_FRAME_ID (0x678u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_FRAME_ID (0x680u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_FRAME_ID (0x681u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_FRAME_ID (0x682u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_FRAME_ID (0x683u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG4_FRAME_ID (0x684u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_FRAME_ID (0x685u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_FRAME_ID (0x686u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_FRAME_ID (0x687u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_FRAME_ID (0x688u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_FRAME_ID (0x690u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_FRAME_ID (0x691u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_FRAME_ID (0x692u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_FRAME_ID (0x693u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG4_FRAME_ID (0x694u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_FRAME_ID (0x695u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_FRAME_ID (0x696u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_FRAME_ID (0x697u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_FRAME_ID (0x698u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_FRAME_ID (0x6a0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_FRAME_ID (0x6a1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_FRAME_ID (0x6a2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_FRAME_ID (0x6a3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG4_FRAME_ID (0x6a4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_FRAME_ID (0x6a5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_FRAME_ID (0x6a6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_FRAME_ID (0x6a7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_FRAME_ID (0x6a8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_FRAME_ID (0x6b0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_FRAME_ID (0x6b1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_FRAME_ID (0x6b2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_FRAME_ID (0x6b3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG4_FRAME_ID (0x6b4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_FRAME_ID (0x6b5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_FRAME_ID (0x6b6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_FRAME_ID (0x6b7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_FRAME_ID (0x6b8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_FRAME_ID (0x6c0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_FRAME_ID (0x6c1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_FRAME_ID (0x6c2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_FRAME_ID (0x6c3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG4_FRAME_ID (0x6c4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_FRAME_ID (0x6c5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_FRAME_ID (0x6c6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_FRAME_ID (0x6c7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_FRAME_ID (0x6c8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_FRAME_ID (0x6d0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_FRAME_ID (0x6d1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_FRAME_ID (0x6d2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_FRAME_ID (0x6d3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG4_FRAME_ID (0x6d4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_FRAME_ID (0x6d5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_FRAME_ID (0x6d6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_FRAME_ID (0x6d7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_FRAME_ID (0x6d8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_FRAME_ID (0x6e0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_FRAME_ID (0x6e1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_FRAME_ID (0x6e2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_FRAME_ID (0x6e3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG4_FRAME_ID (0x6e4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_FRAME_ID (0x6e5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_FRAME_ID (0x6e6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_FRAME_ID (0x6e7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_FRAME_ID (0x6e8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_FRAME_ID (0x6f0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_FRAME_ID (0x6f1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_FRAME_ID (0x6f2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_FRAME_ID (0x6f3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG4_FRAME_ID (0x6f4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_FRAME_ID (0x6f5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_FRAME_ID (0x6f6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_FRAME_ID (0x6f7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_FRAME_ID (0x6f8u)
+#define CAN1__MAIN_FT24_JETSON_RX_FRAME_ID (0xe0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_FRAME_ID (0x8fu)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_FRAME_ID (0x8eu)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_FRAME_ID (0x8du)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_FRAME_ID (0x8cu)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_FRAME_ID (0x8bu)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_FRAME_ID (0x8au)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_FRAME_ID (0x89u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_FRAME_ID (0x88u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_FRAME_ID (0x87u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_FRAME_ID (0x86u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_FRAME_ID (0x85u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_FRAME_ID (0x84u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_FRAME_ID (0x83u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_FRAME_ID (0x82u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_FRAME_ID (0x81u)
+#define CAN1__MAIN_FT24_ABX_MISC_FRAME_ID (0x109u)
+#define CAN1__MAIN_FT24_AMS_ERROR_FRAME_ID (0x0cu)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_FRAME_ID (0x108u)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_FRAME_ID (0x106u)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_FRAME_ID (0x107u)
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_FRAME_ID (0x105u)
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_FRAME_ID (0x104u)
+#define CAN1__MAIN_FT24_ABX_DAMPERS_FRAME_ID (0x103u)
+#define CAN1__MAIN_FT24_ABX_TIMINGS_FRAME_ID (0x102u)
+#define CAN1__MAIN_FT24_ABX_DRIVER_FRAME_ID (0x101u)
+#define CAN1__MAIN_FT24_TTS_CONFIG_FRAME_ID (0x700u)
+#define CAN1__MAIN_FT24_TTS_RR_FRAME_ID (0x704u)
+#define CAN1__MAIN_FT24_TTS_RL_FRAME_ID (0x703u)
+#define CAN1__MAIN_FT24_TTS_FR_FRAME_ID (0x702u)
+#define CAN1__MAIN_FT24_TTS_FL_FRAME_ID (0x701u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_FRAME_ID (0x402u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_FRAME_ID (0x80u)
+#define CAN1__MAIN_FT24_SSU_MESSAGE_FRAME_ID (0x500u)
+#define CAN1__MAIN_FT24_AMS_STATUS_FRAME_ID (0x0au)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_FRAME_ID (0x09u)
+#define CAN1__MAIN_FT24_AMS_IN_FRAME_ID (0x0bu)
+#define CAN1__MAIN_FT24_SHUNT_CURRENT_FRAME_ID (0x521u)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE1_FRAME_ID (0x522u)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE2_FRAME_ID (0x523u)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE3_FRAME_ID (0x524u)
+#define CAN1__MAIN_FT24_SHUNT_TEMPERATURE_FRAME_ID (0x525u)
+#define CAN1__MAIN_FT24_SDCL_TX_FRAME_ID (0x10u)
+#define CAN1__MAIN_FT24_SDCL_RX_FRAME_ID (0x0fu)
+#define CAN1__MAIN_FT24_PDU_COMMAND_FRAME_ID (0xc8u)
+#define CAN1__MAIN_FT24_PDU_RESPONSE_FRAME_ID (0xc9u)
+#define CAN1__MAIN_FT24_TX_PDO_FRAME_ID (0x202u)
+#define CAN1__MAIN_FT24_X_SENS_ERROR_FRAME_ID (0x01u)
+#define CAN1__MAIN_FT24_X_SENS_WARNING_FRAME_ID (0x02u)
+#define CAN1__MAIN_FT24_X_SENS_SAMPLE_TIME_FRAME_ID (0x05u)
+#define CAN1__MAIN_FT24_X_SENS_GROUP_COUNTER_FRAME_ID (0x06u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_FRAME_ID (0x11u)
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_FRAME_ID (0x32u)
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_FRAME_ID (0x34u)
+#define CAN1__MAIN_FT24_X_SENS_LONG_LAT_FRAME_ID (0x71u)
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_FRAME_ID (0x76u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_FRAME_ID (0x410u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_FRAME_ID (0x400u)
+#define CAN1__MAIN_FT24_EPSC_OUT_FRAME_ID (0x321u)
+#define CAN1__MAIN_FT24_EPSC_STEERING_IN_FRAME_ID (0x123u)
+#define CAN1__MAIN_FT24_STW_BUTTONS_FRAME_ID (0x401u)
+#define CAN1__MAIN_FT24_STW_STATUS_FRAME_ID (0x412u)
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_FRAME_ID (0xcau)
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_FRAME_ID (0xcbu)
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_FRAME_ID (0xccu)
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_FRAME_ID (0xcdu)
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_FRAME_ID (0x124u)
+
+/* Frame lengths in bytes. */
+#define CAN1__MAIN_FT24_ABX_PARAM_CONFIRM_LENGTH (1u)
+#define CAN1__MAIN_FT24_ABX_HYDRAULICS_LENGTH (3u)
+#define CAN1__MAIN_FT24_JETSON_TX_LENGTH (7u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG4_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_LENGTH (8u)
+#define CAN1__MAIN_FT24_JETSON_RX_LENGTH (4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_MISC_LENGTH (7u)
+#define CAN1__MAIN_FT24_AMS_ERROR_LENGTH (2u)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_LENGTH (6u)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_DAMPERS_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_TIMINGS_LENGTH (8u)
+#define CAN1__MAIN_FT24_ABX_DRIVER_LENGTH (8u)
+#define CAN1__MAIN_FT24_TTS_CONFIG_LENGTH (1u)
+#define CAN1__MAIN_FT24_TTS_RR_LENGTH (8u)
+#define CAN1__MAIN_FT24_TTS_RL_LENGTH (8u)
+#define CAN1__MAIN_FT24_TTS_FR_LENGTH (8u)
+#define CAN1__MAIN_FT24_TTS_FL_LENGTH (8u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_LENGTH (5u)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_LENGTH (8u)
+#define CAN1__MAIN_FT24_SSU_MESSAGE_LENGTH (4u)
+#define CAN1__MAIN_FT24_AMS_STATUS_LENGTH (6u)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_LENGTH (8u)
+#define CAN1__MAIN_FT24_AMS_IN_LENGTH (1u)
+#define CAN1__MAIN_FT24_SHUNT_CURRENT_LENGTH (6u)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE1_LENGTH (6u)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE2_LENGTH (6u)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE3_LENGTH (6u)
+#define CAN1__MAIN_FT24_SHUNT_TEMPERATURE_LENGTH (6u)
+#define CAN1__MAIN_FT24_SDCL_TX_LENGTH (4u)
+#define CAN1__MAIN_FT24_SDCL_RX_LENGTH (3u)
+#define CAN1__MAIN_FT24_PDU_COMMAND_LENGTH (6u)
+#define CAN1__MAIN_FT24_PDU_RESPONSE_LENGTH (6u)
+#define CAN1__MAIN_FT24_TX_PDO_LENGTH (6u)
+#define CAN1__MAIN_FT24_X_SENS_ERROR_LENGTH (1u)
+#define CAN1__MAIN_FT24_X_SENS_WARNING_LENGTH (1u)
+#define CAN1__MAIN_FT24_X_SENS_SAMPLE_TIME_LENGTH (4u)
+#define CAN1__MAIN_FT24_X_SENS_GROUP_COUNTER_LENGTH (2u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_LENGTH (4u)
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_LENGTH (6u)
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_LENGTH (6u)
+#define CAN1__MAIN_FT24_X_SENS_LONG_LAT_LENGTH (8u)
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_LENGTH (6u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_LENGTH (1u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_LENGTH (1u)
+#define CAN1__MAIN_FT24_EPSC_OUT_LENGTH (8u)
+#define CAN1__MAIN_FT24_EPSC_STEERING_IN_LENGTH (2u)
+#define CAN1__MAIN_FT24_STW_BUTTONS_LENGTH (1u)
+#define CAN1__MAIN_FT24_STW_STATUS_LENGTH (6u)
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_LENGTH (8u)
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_LENGTH (8u)
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_LENGTH (8u)
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_LENGTH (8u)
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_LENGTH (7u)
+
+/* Extended or standard frame types. */
+#define CAN1__MAIN_FT24_ABX_PARAM_CONFIRM_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_HYDRAULICS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_JETSON_TX_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_JETSON_RX_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_MISC_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_ERROR_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_DAMPERS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_TIMINGS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_ABX_DRIVER_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_TTS_CONFIG_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_TTS_RR_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_TTS_RL_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_TTS_FR_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_TTS_FL_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SSU_MESSAGE_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AMS_IN_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SHUNT_CURRENT_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SHUNT_TEMPERATURE_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SDCL_TX_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_SDCL_RX_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_PDU_COMMAND_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_PDU_RESPONSE_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_TX_PDO_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_ERROR_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_WARNING_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_SAMPLE_TIME_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_GROUP_COUNTER_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_LONG_LAT_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_EPSC_OUT_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_EPSC_STEERING_IN_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_STW_BUTTONS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_STW_STATUS_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_IS_EXTENDED (0)
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_IS_EXTENDED (0)
+
+/* Frame cycle times in milliseconds. */
+
+
+/* Signal choices. */
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_NONE_CHOICE (0)
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_SLAVE__TIMEOUT_CHOICE (1)
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_SLAVE__PANIC_CHOICE (2)
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_SHUNT__TIMEOUT_CHOICE (3)
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_SHUNT__OVERCURRENT_CHOICE (4)
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_SHUNT__OVERTEMPERATURE_CHOICE (5)
+
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_BRAKE_BALANCE_CHOICE (0u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TRACTION_CONTROL1_CHOICE (1u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TRACTION_CONTROL2_CHOICE (2u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TORQUE_MAP_CHOICE (3u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TEST1_CHOICE (4u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TEST2_CHOICE (5u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TEST3_CHOICE (6u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_TEST4_CHOICE (7u)
+
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_ASRON_OFF_CHOICE (0u)
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_ASRON_ON_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_AMS_STATUS_AMS_STATE_INACTIVE_CHOICE (0u)
+#define CAN1__MAIN_FT24_AMS_STATUS_AMS_STATE_ACTIVE_CHOICE (1u)
+#define CAN1__MAIN_FT24_AMS_STATUS_AMS_STATE_PRECHARGE_CHOICE (2u)
+#define CAN1__MAIN_FT24_AMS_STATUS_AMS_STATE_DISCHARGE_CHOICE (3u)
+#define CAN1__MAIN_FT24_AMS_STATUS_AMS_STATE_ERROR_CHOICE (4u)
+
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_OVERTEMPERATURE_CHOICE (0u)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_UNDERTEMPERATURE_CHOICE (1u)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_OVERVOLTAGE_CHOICE (2u)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_UNDERVOLTAGE_CHOICE (3u)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_TOO_FEW_WORKING_TEMPERATURE_SENSORS_CHOICE (4u)
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_OPEN_CELL_CONNECTION_CHOICE (5u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_HAVE_GNSS_TIME_PULSE_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_HAVE_GNSS_TIME_PULSE_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RTK_STATUS_NO_RTK_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RTK_STATUS_RTK_FLOATING_CHOICE (1u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RTK_STATUS_RTK_FIXED_CHOICE (2u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_FILTER_MODE_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_FILTER_MODE_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_Z_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_Z_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RETRANSMITTED_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RETRANSMITTED_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIPPING_DETECTED_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIPPING_DETECTED_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_INTERPOLATED_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_INTERPOLATED_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SYNC_IN_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SYNC_IN_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SYNC_OUT_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SYNC_OUT_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_X_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_X_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_Y_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_Y_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_Z_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_Z_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_X_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_X_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_Y_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_Y_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_Z_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_Z_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_X_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_X_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_Y_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_Y_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SELF_TEST_OK_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SELF_TEST_OK_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_ORIENTATION_VALID_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_ORIENTATION_VALID_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_GPS_VALID_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_GPS_VALID_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_NO_ROTATION_ABORTED_CHOICE (1u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_NO_ROTATION_SAMPLES_REJECTED_CHOICE (2u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_NO_ROTATION_RUNNING_NORMALLY_CHOICE (3u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_REPRESENTATIVE_MOTION_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_REPRESENTATIVE_MOTION_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_EXTERNAL_CLOCK_SYNCED_FALSE_CHOICE (0u)
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_EXTERNAL_CLOCK_SYNCED_TRUE_CHOICE (1u)
+
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_ACCELERATION_CHOICE (1u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_SKIDPAD_CHOICE (2u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_TRACKDRIVE_CHOICE (3u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_BRAKETEST_CHOICE (4u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_INSPECTION_CHOICE (5u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_AUTOCROSS_CHOICE (6u)
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_MANUAL_CHOICE (7u)
+
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_ACCELERATION_CHOICE (1u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_SKIDPAD_CHOICE (2u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_TRACKDRIVE_CHOICE (3u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_BRAKETEST_CHOICE (4u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_INSPECTION_CHOICE (5u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_AUTOCROSS_CHOICE (6u)
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_MANUAL_CHOICE (7u)
+
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_OFF_CHOICE (0u)
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_MANUAL_CHOICE (1u)
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_READY_CHOICE (2u)
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_DRIVING_CHOICE (3u)
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_FINISHED_CHOICE (4u)
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_EMERGENCY_CHOICE (5u)
+
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_NONE_CHOICE (0u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_TSMS_CHOICE (1u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_TS_ACTIVE_CHOICE (2u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_RESETTING_NODES_CHOICE (3u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_RESETTING_COMMS_CHOICE (4u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_WAITING_INIT_CHOICE (5u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_INIT_STAGE1_CHOICE (6u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_INIT_STAGE2_CHOICE (7u)
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_INIT_SUCCESS_CHOICE (15u)
+
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_START_CHOICE (0u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_WD_CHECK_CHOICE (1u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_WD_OK_CHOICE (2u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_ASB_CHECK_1_CHOICE (3u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_ASB_CHECK_2_CHOICE (4u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_WAIT_TS_CHOICE (5u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_EBS_CHECK_A_CHOICE (6u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_EBS_CHECK_B_CHOICE (7u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_DONE_CHOICE (8u)
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_ERROR_CHOICE (9u)
+
+/* Frame Names. */
+#define CAN1__MAIN_FT24_ABX_PARAM_CONFIRM_NAME "ABX_ParamConfirm"
+#define CAN1__MAIN_FT24_ABX_HYDRAULICS_NAME "ABX_Hydraulics"
+#define CAN1__MAIN_FT24_JETSON_TX_NAME "JetsonTX"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_NAME "AMS_Slave0_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_NAME "AMS_Slave0_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_NAME "AMS_Slave0_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_NAME "AMS_Slave0_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG4_NAME "AMS_Slave0_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_NAME "AMS_Slave0_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_NAME "AMS_Slave0_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_NAME "AMS_Slave0_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_NAME "AMS_Slave0_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_NAME "AMS_Slave1_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_NAME "AMS_Slave1_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_NAME "AMS_Slave1_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_NAME "AMS_Slave1_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG4_NAME "AMS_Slave1_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_NAME "AMS_Slave1_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_NAME "AMS_Slave1_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_NAME "AMS_Slave1_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_NAME "AMS_Slave1_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_NAME "AMS_Slave2_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_NAME "AMS_Slave2_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_NAME "AMS_Slave2_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_NAME "AMS_Slave2_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG4_NAME "AMS_Slave2_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_NAME "AMS_Slave2_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_NAME "AMS_Slave2_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_NAME "AMS_Slave2_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_NAME "AMS_Slave2_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_NAME "AMS_Slave3_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_NAME "AMS_Slave3_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_NAME "AMS_Slave3_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_NAME "AMS_Slave3_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG4_NAME "AMS_Slave3_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_NAME "AMS_Slave3_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_NAME "AMS_Slave3_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_NAME "AMS_Slave3_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_NAME "AMS_Slave3_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_NAME "AMS_Slave4_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_NAME "AMS_Slave4_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_NAME "AMS_Slave4_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_NAME "AMS_Slave4_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG4_NAME "AMS_Slave4_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_NAME "AMS_Slave4_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_NAME "AMS_Slave4_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_NAME "AMS_Slave4_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_NAME "AMS_Slave4_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_NAME "AMS_Slave5_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_NAME "AMS_Slave5_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_NAME "AMS_Slave5_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_NAME "AMS_Slave5_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG4_NAME "AMS_Slave5_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_NAME "AMS_Slave5_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_NAME "AMS_Slave5_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_NAME "AMS_Slave5_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_NAME "AMS_Slave5_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_NAME "AMS_Slave6_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_NAME "AMS_Slave6_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_NAME "AMS_Slave6_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_NAME "AMS_Slave6_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG4_NAME "AMS_Slave6_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_NAME "AMS_Slave6_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_NAME "AMS_Slave6_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_NAME "AMS_Slave6_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_NAME "AMS_Slave6_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_NAME "AMS_Slave7_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_NAME "AMS_Slave7_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_NAME "AMS_Slave7_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_NAME "AMS_Slave7_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG4_NAME "AMS_Slave7_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_NAME "AMS_Slave7_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_NAME "AMS_Slave7_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_NAME "AMS_Slave7_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_NAME "AMS_Slave7_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_NAME "AMS_Slave8_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_NAME "AMS_Slave8_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_NAME "AMS_Slave8_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_NAME "AMS_Slave8_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG4_NAME "AMS_Slave8_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_NAME "AMS_Slave8_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_NAME "AMS_Slave8_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_NAME "AMS_Slave8_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_NAME "AMS_Slave8_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_NAME "AMS_Slave9_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_NAME "AMS_Slave9_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_NAME "AMS_Slave9_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_NAME "AMS_Slave9_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG4_NAME "AMS_Slave9_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_NAME "AMS_Slave9_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_NAME "AMS_Slave9_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_NAME "AMS_Slave9_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_NAME "AMS_Slave9_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_NAME "AMS_Slave10_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_NAME "AMS_Slave10_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_NAME "AMS_Slave10_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_NAME "AMS_Slave10_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG4_NAME "AMS_Slave10_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_NAME "AMS_Slave10_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_NAME "AMS_Slave10_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_NAME "AMS_Slave10_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_NAME "AMS_Slave10_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_NAME "AMS_Slave11_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_NAME "AMS_Slave11_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_NAME "AMS_Slave11_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_NAME "AMS_Slave11_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG4_NAME "AMS_Slave11_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_NAME "AMS_Slave11_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_NAME "AMS_Slave11_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_NAME "AMS_Slave11_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_NAME "AMS_Slave11_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_NAME "AMS_Slave12_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_NAME "AMS_Slave12_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_NAME "AMS_Slave12_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_NAME "AMS_Slave12_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG4_NAME "AMS_Slave12_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_NAME "AMS_Slave12_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_NAME "AMS_Slave12_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_NAME "AMS_Slave12_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_NAME "AMS_Slave12_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_NAME "AMS_Slave13_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_NAME "AMS_Slave13_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_NAME "AMS_Slave13_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_NAME "AMS_Slave13_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG4_NAME "AMS_Slave13_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_NAME "AMS_Slave13_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_NAME "AMS_Slave13_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_NAME "AMS_Slave13_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_NAME "AMS_Slave13_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_NAME "AMS_Slave14_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_NAME "AMS_Slave14_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_NAME "AMS_Slave14_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_NAME "AMS_Slave14_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG4_NAME "AMS_Slave14_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_NAME "AMS_Slave14_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_NAME "AMS_Slave14_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_NAME "AMS_Slave14_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_NAME "AMS_Slave14_Log8"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_NAME "AMS_Slave15_Log0"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_NAME "AMS_Slave15_Log1"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_NAME "AMS_Slave15_Log2"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_NAME "AMS_Slave15_Log3"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG4_NAME "AMS_Slave15_Log4"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_NAME "AMS_Slave15_Log5"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_NAME "AMS_Slave15_Log6"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_NAME "AMS_Slave15_Log7"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_NAME "AMS_Slave15_Log8"
+#define CAN1__MAIN_FT24_JETSON_RX_NAME "JetsonRX"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_NAME "AMS_Slave15Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_NAME "AMS_Slave14Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_NAME "AMS_Slave13Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_NAME "AMS_Slave12Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_NAME "AMS_Slave11Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_NAME "AMS_Slave10Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_NAME "AMS_Slave9Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_NAME "AMS_Slave8Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_NAME "AMS_Slave7Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_NAME "AMS_Slave6Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_NAME "AMS_Slave5Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_NAME "AMS_Slave4Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_NAME "AMS_Slave3Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_NAME "AMS_Slave2Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_NAME "AMS_Slave1Status"
+#define CAN1__MAIN_FT24_ABX_MISC_NAME "ABX_Misc"
+#define CAN1__MAIN_FT24_AMS_ERROR_NAME "AMS_Error"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_NAME "ABX_CoolingSys_Internal"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_NAME "ABX_CoolingSys_Acc"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_NAME "ABX_CoolingSys_MotInv"
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_NAME "ABX_BrakeT"
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_NAME "ABX_Wheelspeed"
+#define CAN1__MAIN_FT24_ABX_DAMPERS_NAME "ABX_Dampers"
+#define CAN1__MAIN_FT24_ABX_TIMINGS_NAME "ABX_Timings"
+#define CAN1__MAIN_FT24_ABX_DRIVER_NAME "ABX_Driver"
+#define CAN1__MAIN_FT24_TTS_CONFIG_NAME "TTS_Config"
+#define CAN1__MAIN_FT24_TTS_RR_NAME "TTS_RR"
+#define CAN1__MAIN_FT24_TTS_RL_NAME "TTS_RL"
+#define CAN1__MAIN_FT24_TTS_FR_NAME "TTS_FR"
+#define CAN1__MAIN_FT24_TTS_FL_NAME "TTS_FL"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_NAME "STW_Param_Set"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_NAME "AMS_Slave0Status"
+#define CAN1__MAIN_FT24_SSU_MESSAGE_NAME "SSU_Message"
+#define CAN1__MAIN_FT24_AMS_STATUS_NAME "AMS_Status"
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_NAME "AMS_SlavePanic"
+#define CAN1__MAIN_FT24_AMS_IN_NAME "AMS_In"
+#define CAN1__MAIN_FT24_SHUNT_CURRENT_NAME "Shunt_Current"
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE1_NAME "Shunt_Voltage1"
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE2_NAME "Shunt_Voltage2"
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE3_NAME "Shunt_Voltage3"
+#define CAN1__MAIN_FT24_SHUNT_TEMPERATURE_NAME "Shunt_Temperature"
+#define CAN1__MAIN_FT24_SDCL_TX_NAME "SDCL_tx"
+#define CAN1__MAIN_FT24_SDCL_RX_NAME "SDCL_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_NAME "PDU_Command"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_NAME "PDU_Response"
+#define CAN1__MAIN_FT24_TX_PDO_NAME "TxPDO"
+#define CAN1__MAIN_FT24_X_SENS_ERROR_NAME "XSens_Error"
+#define CAN1__MAIN_FT24_X_SENS_WARNING_NAME "XSens_Warning"
+#define CAN1__MAIN_FT24_X_SENS_SAMPLE_TIME_NAME "XSens_SampleTime"
+#define CAN1__MAIN_FT24_X_SENS_GROUP_COUNTER_NAME "XSens_GroupCounter"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_NAME "XSens_StatusWord"
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_NAME "XSens_RateOfTurn"
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_NAME "XSens_Acceleration"
+#define CAN1__MAIN_FT24_X_SENS_LONG_LAT_NAME "XSens_LongLat"
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_NAME "XSens_Velocity"
+#define CAN1__MAIN_FT24_AS_MISSION_FB_NAME "AS_Mission_fb"
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_NAME "STW_mission_selected"
+#define CAN1__MAIN_FT24_EPSC_OUT_NAME "EPSC_out"
+#define CAN1__MAIN_FT24_EPSC_STEERING_IN_NAME "EPSC_Steering_In"
+#define CAN1__MAIN_FT24_STW_BUTTONS_NAME "STW_buttons"
+#define CAN1__MAIN_FT24_STW_STATUS_NAME "STW_status"
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_NAME "PDU_Current_1"
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_NAME "PDU_Current_2"
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_NAME "PDU_Current_3"
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_NAME "PDU_Current_4"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_NAME "EPSC_Config_In"
+
+/* Signal Names. */
+#define CAN1__MAIN_FT24_ABX_PARAM_CONFIRM_ABX_PARAM_CONFIRM_NAME "ABX_ParamConfirm"
+#define CAN1__MAIN_FT24_ABX_HYDRAULICS_ABX_HYD_PA_NAME "ABX_Hyd_PA"
+#define CAN1__MAIN_FT24_ABX_HYDRAULICS_ABX_HYD_PB_NAME "ABX_Hyd_PB"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_AS_MISSION_COMPLETE_NAME "Jetson_AS_Mission_Complete"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_AS_OK_NAME "Jetson_AS_OK"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_LAP_COUNT_NAME "Jetson_Lap_Count"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_SPEED_TARGET_NAME "Jetson_Speed_Target"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_STEERING_ANGLE_NAME "Jetson_Steering_Angle"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_BRAKE_RATIO_NAME "Jetson_Brake_Ratio"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_TORQUE_RATIO_NAME "Jetson_Torque_Ratio"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_CONES_ALL_NAME "Jetson_Cones_All"
+#define CAN1__MAIN_FT24_JETSON_TX_JETSON_CONES_ACTUAL_NAME "Jetson_Cones_Actual"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_AMS_SLAVE0_V0_NAME "AMS_Slave0_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_AMS_SLAVE0_V1_NAME "AMS_Slave0_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_AMS_SLAVE0_V2_NAME "AMS_Slave0_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG0_AMS_SLAVE0_V3_NAME "AMS_Slave0_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_AMS_SLAVE0_V4_NAME "AMS_Slave0_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_AMS_SLAVE0_V5_NAME "AMS_Slave0_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_AMS_SLAVE0_V6_NAME "AMS_Slave0_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG1_AMS_SLAVE0_V7_NAME "AMS_Slave0_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_AMS_SLAVE0_V8_NAME "AMS_Slave0_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_AMS_SLAVE0_V9_NAME "AMS_Slave0_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_AMS_SLAVE0_V10_NAME "AMS_Slave0_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG2_AMS_SLAVE0_V11_NAME "AMS_Slave0_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_AMS_SLAVE0_V12_NAME "AMS_Slave0_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_AMS_SLAVE0_V13_NAME "AMS_Slave0_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_AMS_SLAVE0_V14_NAME "AMS_Slave0_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG3_AMS_SLAVE0_V15_NAME "AMS_Slave0_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG4_AMS_SLAVE0_V16_NAME "AMS_Slave0_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG4_AMS_SLAVE0_FAILED_SENSORS_NAME "AMS_Slave0_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T0_NAME "AMS_Slave0_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T1_NAME "AMS_Slave0_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T2_NAME "AMS_Slave0_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T3_NAME "AMS_Slave0_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T4_NAME "AMS_Slave0_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T5_NAME "AMS_Slave0_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T6_NAME "AMS_Slave0_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG5_AMS_SLAVE0_T7_NAME "AMS_Slave0_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T8_NAME "AMS_Slave0_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T9_NAME "AMS_Slave0_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T10_NAME "AMS_Slave0_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T11_NAME "AMS_Slave0_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T12_NAME "AMS_Slave0_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T13_NAME "AMS_Slave0_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T14_NAME "AMS_Slave0_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG6_AMS_SLAVE0_T15_NAME "AMS_Slave0_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T16_NAME "AMS_Slave0_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T17_NAME "AMS_Slave0_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T18_NAME "AMS_Slave0_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T19_NAME "AMS_Slave0_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T20_NAME "AMS_Slave0_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T21_NAME "AMS_Slave0_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T22_NAME "AMS_Slave0_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG7_AMS_SLAVE0_T23_NAME "AMS_Slave0_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T24_NAME "AMS_Slave0_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T25_NAME "AMS_Slave0_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T26_NAME "AMS_Slave0_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T27_NAME "AMS_Slave0_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T28_NAME "AMS_Slave0_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T29_NAME "AMS_Slave0_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T30_NAME "AMS_Slave0_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_LOG8_AMS_SLAVE0_T31_NAME "AMS_Slave0_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_AMS_SLAVE1_V0_NAME "AMS_Slave1_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_AMS_SLAVE1_V1_NAME "AMS_Slave1_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_AMS_SLAVE1_V2_NAME "AMS_Slave1_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG0_AMS_SLAVE1_V3_NAME "AMS_Slave1_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_AMS_SLAVE1_V4_NAME "AMS_Slave1_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_AMS_SLAVE1_V5_NAME "AMS_Slave1_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_AMS_SLAVE1_V6_NAME "AMS_Slave1_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG1_AMS_SLAVE1_V7_NAME "AMS_Slave1_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_AMS_SLAVE1_V8_NAME "AMS_Slave1_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_AMS_SLAVE1_V9_NAME "AMS_Slave1_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_AMS_SLAVE1_V10_NAME "AMS_Slave1_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG2_AMS_SLAVE1_V11_NAME "AMS_Slave1_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_AMS_SLAVE1_V12_NAME "AMS_Slave1_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_AMS_SLAVE1_V13_NAME "AMS_Slave1_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_AMS_SLAVE1_V14_NAME "AMS_Slave1_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG3_AMS_SLAVE1_V15_NAME "AMS_Slave1_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG4_AMS_SLAVE1_V16_NAME "AMS_Slave1_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG4_AMS_SLAVE1_FAILED_SENSORS_NAME "AMS_Slave1_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T0_NAME "AMS_Slave1_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T1_NAME "AMS_Slave1_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T2_NAME "AMS_Slave1_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T3_NAME "AMS_Slave1_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T4_NAME "AMS_Slave1_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T5_NAME "AMS_Slave1_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T6_NAME "AMS_Slave1_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG5_AMS_SLAVE1_T7_NAME "AMS_Slave1_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T8_NAME "AMS_Slave1_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T9_NAME "AMS_Slave1_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T10_NAME "AMS_Slave1_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T11_NAME "AMS_Slave1_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T12_NAME "AMS_Slave1_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T13_NAME "AMS_Slave1_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T14_NAME "AMS_Slave1_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG6_AMS_SLAVE1_T15_NAME "AMS_Slave1_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T16_NAME "AMS_Slave1_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T17_NAME "AMS_Slave1_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T18_NAME "AMS_Slave1_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T19_NAME "AMS_Slave1_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T20_NAME "AMS_Slave1_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T21_NAME "AMS_Slave1_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T22_NAME "AMS_Slave1_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG7_AMS_SLAVE1_T23_NAME "AMS_Slave1_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T24_NAME "AMS_Slave1_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T25_NAME "AMS_Slave1_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T26_NAME "AMS_Slave1_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T27_NAME "AMS_Slave1_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T28_NAME "AMS_Slave1_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T29_NAME "AMS_Slave1_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T30_NAME "AMS_Slave1_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_LOG8_AMS_SLAVE1_T31_NAME "AMS_Slave1_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_AMS_SLAVE2_V0_NAME "AMS_Slave2_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_AMS_SLAVE2_V1_NAME "AMS_Slave2_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_AMS_SLAVE2_V2_NAME "AMS_Slave2_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG0_AMS_SLAVE2_V3_NAME "AMS_Slave2_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_AMS_SLAVE2_V4_NAME "AMS_Slave2_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_AMS_SLAVE2_V5_NAME "AMS_Slave2_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_AMS_SLAVE2_V6_NAME "AMS_Slave2_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG1_AMS_SLAVE2_V7_NAME "AMS_Slave2_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_AMS_SLAVE2_V8_NAME "AMS_Slave2_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_AMS_SLAVE2_V9_NAME "AMS_Slave2_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_AMS_SLAVE2_V10_NAME "AMS_Slave2_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG2_AMS_SLAVE2_V11_NAME "AMS_Slave2_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_AMS_SLAVE2_V12_NAME "AMS_Slave2_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_AMS_SLAVE2_V13_NAME "AMS_Slave2_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_AMS_SLAVE2_V14_NAME "AMS_Slave2_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG3_AMS_SLAVE2_V15_NAME "AMS_Slave2_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG4_AMS_SLAVE2_V16_NAME "AMS_Slave2_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG4_AMS_SLAVE2_FAILED_SENSORS_NAME "AMS_Slave2_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T0_NAME "AMS_Slave2_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T1_NAME "AMS_Slave2_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T2_NAME "AMS_Slave2_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T3_NAME "AMS_Slave2_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T4_NAME "AMS_Slave2_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T5_NAME "AMS_Slave2_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T6_NAME "AMS_Slave2_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG5_AMS_SLAVE2_T7_NAME "AMS_Slave2_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T8_NAME "AMS_Slave2_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T9_NAME "AMS_Slave2_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T10_NAME "AMS_Slave2_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T11_NAME "AMS_Slave2_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T12_NAME "AMS_Slave2_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T13_NAME "AMS_Slave2_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T14_NAME "AMS_Slave2_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG6_AMS_SLAVE2_T15_NAME "AMS_Slave2_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T16_NAME "AMS_Slave2_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T17_NAME "AMS_Slave2_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T18_NAME "AMS_Slave2_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T19_NAME "AMS_Slave2_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T20_NAME "AMS_Slave2_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T21_NAME "AMS_Slave2_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T22_NAME "AMS_Slave2_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG7_AMS_SLAVE2_T23_NAME "AMS_Slave2_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T24_NAME "AMS_Slave2_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T25_NAME "AMS_Slave2_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T26_NAME "AMS_Slave2_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T27_NAME "AMS_Slave2_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T28_NAME "AMS_Slave2_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T29_NAME "AMS_Slave2_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T30_NAME "AMS_Slave2_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_LOG8_AMS_SLAVE2_T31_NAME "AMS_Slave2_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_AMS_SLAVE3_V0_NAME "AMS_Slave3_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_AMS_SLAVE3_V1_NAME "AMS_Slave3_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_AMS_SLAVE3_V2_NAME "AMS_Slave3_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG0_AMS_SLAVE3_V3_NAME "AMS_Slave3_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_AMS_SLAVE3_V4_NAME "AMS_Slave3_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_AMS_SLAVE3_V5_NAME "AMS_Slave3_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_AMS_SLAVE3_V6_NAME "AMS_Slave3_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG1_AMS_SLAVE3_V7_NAME "AMS_Slave3_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_AMS_SLAVE3_V8_NAME "AMS_Slave3_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_AMS_SLAVE3_V9_NAME "AMS_Slave3_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_AMS_SLAVE3_V10_NAME "AMS_Slave3_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG2_AMS_SLAVE3_V11_NAME "AMS_Slave3_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_AMS_SLAVE3_V12_NAME "AMS_Slave3_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_AMS_SLAVE3_V13_NAME "AMS_Slave3_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_AMS_SLAVE3_V14_NAME "AMS_Slave3_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG3_AMS_SLAVE3_V15_NAME "AMS_Slave3_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG4_AMS_SLAVE3_V16_NAME "AMS_Slave3_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG4_AMS_SLAVE3_FAILED_SENSORS_NAME "AMS_Slave3_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T0_NAME "AMS_Slave3_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T1_NAME "AMS_Slave3_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T2_NAME "AMS_Slave3_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T3_NAME "AMS_Slave3_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T4_NAME "AMS_Slave3_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T5_NAME "AMS_Slave3_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T6_NAME "AMS_Slave3_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG5_AMS_SLAVE3_T7_NAME "AMS_Slave3_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T8_NAME "AMS_Slave3_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T9_NAME "AMS_Slave3_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T10_NAME "AMS_Slave3_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T11_NAME "AMS_Slave3_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T12_NAME "AMS_Slave3_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T13_NAME "AMS_Slave3_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T14_NAME "AMS_Slave3_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG6_AMS_SLAVE3_T15_NAME "AMS_Slave3_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T16_NAME "AMS_Slave3_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T17_NAME "AMS_Slave3_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T18_NAME "AMS_Slave3_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T19_NAME "AMS_Slave3_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T20_NAME "AMS_Slave3_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T21_NAME "AMS_Slave3_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T22_NAME "AMS_Slave3_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG7_AMS_SLAVE3_T23_NAME "AMS_Slave3_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T24_NAME "AMS_Slave3_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T25_NAME "AMS_Slave3_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T26_NAME "AMS_Slave3_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T27_NAME "AMS_Slave3_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T28_NAME "AMS_Slave3_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T29_NAME "AMS_Slave3_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T30_NAME "AMS_Slave3_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_LOG8_AMS_SLAVE3_T31_NAME "AMS_Slave3_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_AMS_SLAVE4_V0_NAME "AMS_Slave4_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_AMS_SLAVE4_V1_NAME "AMS_Slave4_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_AMS_SLAVE4_V2_NAME "AMS_Slave4_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG0_AMS_SLAVE4_V3_NAME "AMS_Slave4_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_AMS_SLAVE4_V4_NAME "AMS_Slave4_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_AMS_SLAVE4_V5_NAME "AMS_Slave4_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_AMS_SLAVE4_V6_NAME "AMS_Slave4_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG1_AMS_SLAVE4_V7_NAME "AMS_Slave4_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_AMS_SLAVE4_V8_NAME "AMS_Slave4_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_AMS_SLAVE4_V9_NAME "AMS_Slave4_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_AMS_SLAVE4_V10_NAME "AMS_Slave4_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG2_AMS_SLAVE4_V11_NAME "AMS_Slave4_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_AMS_SLAVE4_V12_NAME "AMS_Slave4_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_AMS_SLAVE4_V13_NAME "AMS_Slave4_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_AMS_SLAVE4_V14_NAME "AMS_Slave4_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG3_AMS_SLAVE4_V15_NAME "AMS_Slave4_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG4_AMS_SLAVE4_V16_NAME "AMS_Slave4_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG4_AMS_SLAVE4_FAILED_SENSORS_NAME "AMS_Slave4_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T0_NAME "AMS_Slave4_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T1_NAME "AMS_Slave4_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T2_NAME "AMS_Slave4_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T3_NAME "AMS_Slave4_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T4_NAME "AMS_Slave4_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T5_NAME "AMS_Slave4_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T6_NAME "AMS_Slave4_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG5_AMS_SLAVE4_T7_NAME "AMS_Slave4_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T8_NAME "AMS_Slave4_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T9_NAME "AMS_Slave4_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T10_NAME "AMS_Slave4_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T11_NAME "AMS_Slave4_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T12_NAME "AMS_Slave4_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T13_NAME "AMS_Slave4_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T14_NAME "AMS_Slave4_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG6_AMS_SLAVE4_T15_NAME "AMS_Slave4_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T16_NAME "AMS_Slave4_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T17_NAME "AMS_Slave4_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T18_NAME "AMS_Slave4_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T19_NAME "AMS_Slave4_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T20_NAME "AMS_Slave4_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T21_NAME "AMS_Slave4_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T22_NAME "AMS_Slave4_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG7_AMS_SLAVE4_T23_NAME "AMS_Slave4_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T24_NAME "AMS_Slave4_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T25_NAME "AMS_Slave4_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T26_NAME "AMS_Slave4_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T27_NAME "AMS_Slave4_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T28_NAME "AMS_Slave4_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T29_NAME "AMS_Slave4_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T30_NAME "AMS_Slave4_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_LOG8_AMS_SLAVE4_T31_NAME "AMS_Slave4_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_AMS_SLAVE5_V0_NAME "AMS_Slave5_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_AMS_SLAVE5_V1_NAME "AMS_Slave5_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_AMS_SLAVE5_V2_NAME "AMS_Slave5_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG0_AMS_SLAVE5_V3_NAME "AMS_Slave5_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_AMS_SLAVE5_V4_NAME "AMS_Slave5_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_AMS_SLAVE5_V5_NAME "AMS_Slave5_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_AMS_SLAVE5_V6_NAME "AMS_Slave5_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG1_AMS_SLAVE5_V7_NAME "AMS_Slave5_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_AMS_SLAVE5_V8_NAME "AMS_Slave5_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_AMS_SLAVE5_V9_NAME "AMS_Slave5_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_AMS_SLAVE5_V10_NAME "AMS_Slave5_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG2_AMS_SLAVE5_V11_NAME "AMS_Slave5_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_AMS_SLAVE5_V12_NAME "AMS_Slave5_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_AMS_SLAVE5_V13_NAME "AMS_Slave5_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_AMS_SLAVE5_V14_NAME "AMS_Slave5_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG3_AMS_SLAVE5_V15_NAME "AMS_Slave5_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG4_AMS_SLAVE5_V16_NAME "AMS_Slave5_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG4_AMS_SLAVE5_FAILED_SENSORS_NAME "AMS_Slave5_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T0_NAME "AMS_Slave5_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T1_NAME "AMS_Slave5_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T2_NAME "AMS_Slave5_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T3_NAME "AMS_Slave5_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T4_NAME "AMS_Slave5_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T5_NAME "AMS_Slave5_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T6_NAME "AMS_Slave5_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG5_AMS_SLAVE5_T7_NAME "AMS_Slave5_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T8_NAME "AMS_Slave5_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T9_NAME "AMS_Slave5_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T10_NAME "AMS_Slave5_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T11_NAME "AMS_Slave5_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T12_NAME "AMS_Slave5_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T13_NAME "AMS_Slave5_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T14_NAME "AMS_Slave5_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG6_AMS_SLAVE5_T15_NAME "AMS_Slave5_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T16_NAME "AMS_Slave5_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T17_NAME "AMS_Slave5_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T18_NAME "AMS_Slave5_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T19_NAME "AMS_Slave5_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T20_NAME "AMS_Slave5_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T21_NAME "AMS_Slave5_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T22_NAME "AMS_Slave5_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG7_AMS_SLAVE5_T23_NAME "AMS_Slave5_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T24_NAME "AMS_Slave5_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T25_NAME "AMS_Slave5_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T26_NAME "AMS_Slave5_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T27_NAME "AMS_Slave5_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T28_NAME "AMS_Slave5_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T29_NAME "AMS_Slave5_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T30_NAME "AMS_Slave5_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_LOG8_AMS_SLAVE5_T31_NAME "AMS_Slave5_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_AMS_SLAVE6_V0_NAME "AMS_Slave6_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_AMS_SLAVE6_V1_NAME "AMS_Slave6_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_AMS_SLAVE6_V2_NAME "AMS_Slave6_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG0_AMS_SLAVE6_V3_NAME "AMS_Slave6_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_AMS_SLAVE6_V4_NAME "AMS_Slave6_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_AMS_SLAVE6_V5_NAME "AMS_Slave6_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_AMS_SLAVE6_V6_NAME "AMS_Slave6_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG1_AMS_SLAVE6_V7_NAME "AMS_Slave6_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_AMS_SLAVE6_V8_NAME "AMS_Slave6_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_AMS_SLAVE6_V9_NAME "AMS_Slave6_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_AMS_SLAVE6_V10_NAME "AMS_Slave6_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG2_AMS_SLAVE6_V11_NAME "AMS_Slave6_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_AMS_SLAVE6_V12_NAME "AMS_Slave6_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_AMS_SLAVE6_V13_NAME "AMS_Slave6_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_AMS_SLAVE6_V14_NAME "AMS_Slave6_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG3_AMS_SLAVE6_V15_NAME "AMS_Slave6_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG4_AMS_SLAVE6_V16_NAME "AMS_Slave6_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG4_AMS_SLAVE6_FAILED_SENSORS_NAME "AMS_Slave6_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T0_NAME "AMS_Slave6_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T1_NAME "AMS_Slave6_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T2_NAME "AMS_Slave6_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T3_NAME "AMS_Slave6_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T4_NAME "AMS_Slave6_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T5_NAME "AMS_Slave6_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T6_NAME "AMS_Slave6_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG5_AMS_SLAVE6_T7_NAME "AMS_Slave6_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T8_NAME "AMS_Slave6_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T9_NAME "AMS_Slave6_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T10_NAME "AMS_Slave6_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T11_NAME "AMS_Slave6_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T12_NAME "AMS_Slave6_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T13_NAME "AMS_Slave6_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T14_NAME "AMS_Slave6_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG6_AMS_SLAVE6_T15_NAME "AMS_Slave6_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T16_NAME "AMS_Slave6_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T17_NAME "AMS_Slave6_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T18_NAME "AMS_Slave6_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T19_NAME "AMS_Slave6_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T20_NAME "AMS_Slave6_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T21_NAME "AMS_Slave6_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T22_NAME "AMS_Slave6_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG7_AMS_SLAVE6_T23_NAME "AMS_Slave6_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T24_NAME "AMS_Slave6_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T25_NAME "AMS_Slave6_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T26_NAME "AMS_Slave6_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T27_NAME "AMS_Slave6_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T28_NAME "AMS_Slave6_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T29_NAME "AMS_Slave6_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T30_NAME "AMS_Slave6_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_LOG8_AMS_SLAVE6_T31_NAME "AMS_Slave6_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_AMS_SLAVE7_V0_NAME "AMS_Slave7_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_AMS_SLAVE7_V1_NAME "AMS_Slave7_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_AMS_SLAVE7_V2_NAME "AMS_Slave7_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG0_AMS_SLAVE7_V3_NAME "AMS_Slave7_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_AMS_SLAVE7_V4_NAME "AMS_Slave7_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_AMS_SLAVE7_V5_NAME "AMS_Slave7_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_AMS_SLAVE7_V6_NAME "AMS_Slave7_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG1_AMS_SLAVE7_V7_NAME "AMS_Slave7_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_AMS_SLAVE7_V8_NAME "AMS_Slave7_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_AMS_SLAVE7_V9_NAME "AMS_Slave7_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_AMS_SLAVE7_V10_NAME "AMS_Slave7_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG2_AMS_SLAVE7_V11_NAME "AMS_Slave7_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_AMS_SLAVE7_V12_NAME "AMS_Slave7_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_AMS_SLAVE7_V13_NAME "AMS_Slave7_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_AMS_SLAVE7_V14_NAME "AMS_Slave7_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG3_AMS_SLAVE7_V15_NAME "AMS_Slave7_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG4_AMS_SLAVE7_V16_NAME "AMS_Slave7_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG4_AMS_SLAVE7_FAILED_SENSORS_NAME "AMS_Slave7_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T0_NAME "AMS_Slave7_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T1_NAME "AMS_Slave7_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T2_NAME "AMS_Slave7_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T3_NAME "AMS_Slave7_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T4_NAME "AMS_Slave7_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T5_NAME "AMS_Slave7_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T6_NAME "AMS_Slave7_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG5_AMS_SLAVE7_T7_NAME "AMS_Slave7_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T8_NAME "AMS_Slave7_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T9_NAME "AMS_Slave7_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T10_NAME "AMS_Slave7_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T11_NAME "AMS_Slave7_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T12_NAME "AMS_Slave7_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T13_NAME "AMS_Slave7_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T14_NAME "AMS_Slave7_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG6_AMS_SLAVE7_T15_NAME "AMS_Slave7_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T16_NAME "AMS_Slave7_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T17_NAME "AMS_Slave7_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T18_NAME "AMS_Slave7_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T19_NAME "AMS_Slave7_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T20_NAME "AMS_Slave7_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T21_NAME "AMS_Slave7_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T22_NAME "AMS_Slave7_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG7_AMS_SLAVE7_T23_NAME "AMS_Slave7_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T24_NAME "AMS_Slave7_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T25_NAME "AMS_Slave7_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T26_NAME "AMS_Slave7_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T27_NAME "AMS_Slave7_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T28_NAME "AMS_Slave7_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T29_NAME "AMS_Slave7_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T30_NAME "AMS_Slave7_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_LOG8_AMS_SLAVE7_T31_NAME "AMS_Slave7_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_AMS_SLAVE8_V0_NAME "AMS_Slave8_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_AMS_SLAVE8_V1_NAME "AMS_Slave8_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_AMS_SLAVE8_V2_NAME "AMS_Slave8_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG0_AMS_SLAVE8_V3_NAME "AMS_Slave8_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_AMS_SLAVE8_V4_NAME "AMS_Slave8_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_AMS_SLAVE8_V5_NAME "AMS_Slave8_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_AMS_SLAVE8_V6_NAME "AMS_Slave8_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG1_AMS_SLAVE8_V7_NAME "AMS_Slave8_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_AMS_SLAVE8_V8_NAME "AMS_Slave8_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_AMS_SLAVE8_V9_NAME "AMS_Slave8_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_AMS_SLAVE8_V10_NAME "AMS_Slave8_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG2_AMS_SLAVE8_V11_NAME "AMS_Slave8_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_AMS_SLAVE8_V12_NAME "AMS_Slave8_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_AMS_SLAVE8_V13_NAME "AMS_Slave8_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_AMS_SLAVE8_V14_NAME "AMS_Slave8_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG3_AMS_SLAVE8_V15_NAME "AMS_Slave8_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG4_AMS_SLAVE8_V16_NAME "AMS_Slave8_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG4_AMS_SLAVE8_FAILED_SENSORS_NAME "AMS_Slave8_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T0_NAME "AMS_Slave8_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T1_NAME "AMS_Slave8_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T2_NAME "AMS_Slave8_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T3_NAME "AMS_Slave8_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T4_NAME "AMS_Slave8_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T5_NAME "AMS_Slave8_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T6_NAME "AMS_Slave8_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG5_AMS_SLAVE8_T7_NAME "AMS_Slave8_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T8_NAME "AMS_Slave8_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T9_NAME "AMS_Slave8_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T10_NAME "AMS_Slave8_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T11_NAME "AMS_Slave8_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T12_NAME "AMS_Slave8_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T13_NAME "AMS_Slave8_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T14_NAME "AMS_Slave8_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG6_AMS_SLAVE8_T15_NAME "AMS_Slave8_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T16_NAME "AMS_Slave8_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T17_NAME "AMS_Slave8_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T18_NAME "AMS_Slave8_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T19_NAME "AMS_Slave8_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T20_NAME "AMS_Slave8_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T21_NAME "AMS_Slave8_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T22_NAME "AMS_Slave8_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG7_AMS_SLAVE8_T23_NAME "AMS_Slave8_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T24_NAME "AMS_Slave8_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T25_NAME "AMS_Slave8_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T26_NAME "AMS_Slave8_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T27_NAME "AMS_Slave8_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T28_NAME "AMS_Slave8_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T29_NAME "AMS_Slave8_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T30_NAME "AMS_Slave8_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_LOG8_AMS_SLAVE8_T31_NAME "AMS_Slave8_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_AMS_SLAVE9_V0_NAME "AMS_Slave9_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_AMS_SLAVE9_V1_NAME "AMS_Slave9_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_AMS_SLAVE9_V2_NAME "AMS_Slave9_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG0_AMS_SLAVE9_V3_NAME "AMS_Slave9_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_AMS_SLAVE9_V4_NAME "AMS_Slave9_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_AMS_SLAVE9_V5_NAME "AMS_Slave9_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_AMS_SLAVE9_V6_NAME "AMS_Slave9_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG1_AMS_SLAVE9_V7_NAME "AMS_Slave9_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_AMS_SLAVE9_V8_NAME "AMS_Slave9_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_AMS_SLAVE9_V9_NAME "AMS_Slave9_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_AMS_SLAVE9_V10_NAME "AMS_Slave9_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG2_AMS_SLAVE9_V11_NAME "AMS_Slave9_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_AMS_SLAVE9_V12_NAME "AMS_Slave9_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_AMS_SLAVE9_V13_NAME "AMS_Slave9_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_AMS_SLAVE9_V14_NAME "AMS_Slave9_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG3_AMS_SLAVE9_V15_NAME "AMS_Slave9_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG4_AMS_SLAVE9_V16_NAME "AMS_Slave9_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG4_AMS_SLAVE9_FAILED_SENSORS_NAME "AMS_Slave9_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T0_NAME "AMS_Slave9_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T1_NAME "AMS_Slave9_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T2_NAME "AMS_Slave9_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T3_NAME "AMS_Slave9_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T4_NAME "AMS_Slave9_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T5_NAME "AMS_Slave9_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T6_NAME "AMS_Slave9_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG5_AMS_SLAVE9_T7_NAME "AMS_Slave9_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T8_NAME "AMS_Slave9_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T9_NAME "AMS_Slave9_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T10_NAME "AMS_Slave9_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T11_NAME "AMS_Slave9_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T12_NAME "AMS_Slave9_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T13_NAME "AMS_Slave9_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T14_NAME "AMS_Slave9_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG6_AMS_SLAVE9_T15_NAME "AMS_Slave9_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T16_NAME "AMS_Slave9_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T17_NAME "AMS_Slave9_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T18_NAME "AMS_Slave9_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T19_NAME "AMS_Slave9_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T20_NAME "AMS_Slave9_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T21_NAME "AMS_Slave9_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T22_NAME "AMS_Slave9_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG7_AMS_SLAVE9_T23_NAME "AMS_Slave9_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T24_NAME "AMS_Slave9_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T25_NAME "AMS_Slave9_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T26_NAME "AMS_Slave9_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T27_NAME "AMS_Slave9_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T28_NAME "AMS_Slave9_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T29_NAME "AMS_Slave9_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T30_NAME "AMS_Slave9_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_LOG8_AMS_SLAVE9_T31_NAME "AMS_Slave9_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_AMS_SLAVE10_V0_NAME "AMS_Slave10_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_AMS_SLAVE10_V1_NAME "AMS_Slave10_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_AMS_SLAVE10_V2_NAME "AMS_Slave10_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG0_AMS_SLAVE10_V3_NAME "AMS_Slave10_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_AMS_SLAVE10_V4_NAME "AMS_Slave10_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_AMS_SLAVE10_V5_NAME "AMS_Slave10_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_AMS_SLAVE10_V6_NAME "AMS_Slave10_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG1_AMS_SLAVE10_V7_NAME "AMS_Slave10_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_AMS_SLAVE10_V8_NAME "AMS_Slave10_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_AMS_SLAVE10_V9_NAME "AMS_Slave10_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_AMS_SLAVE10_V10_NAME "AMS_Slave10_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG2_AMS_SLAVE10_V11_NAME "AMS_Slave10_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_AMS_SLAVE10_V12_NAME "AMS_Slave10_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_AMS_SLAVE10_V13_NAME "AMS_Slave10_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_AMS_SLAVE10_V14_NAME "AMS_Slave10_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG3_AMS_SLAVE10_V15_NAME "AMS_Slave10_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG4_AMS_SLAVE10_V16_NAME "AMS_Slave10_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG4_AMS_SLAVE10_FAILED_SENSORS_NAME "AMS_Slave10_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T0_NAME "AMS_Slave10_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T1_NAME "AMS_Slave10_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T2_NAME "AMS_Slave10_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T3_NAME "AMS_Slave10_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T4_NAME "AMS_Slave10_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T5_NAME "AMS_Slave10_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T6_NAME "AMS_Slave10_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG5_AMS_SLAVE10_T7_NAME "AMS_Slave10_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T8_NAME "AMS_Slave10_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T9_NAME "AMS_Slave10_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T10_NAME "AMS_Slave10_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T11_NAME "AMS_Slave10_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T12_NAME "AMS_Slave10_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T13_NAME "AMS_Slave10_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T14_NAME "AMS_Slave10_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG6_AMS_SLAVE10_T15_NAME "AMS_Slave10_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T16_NAME "AMS_Slave10_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T17_NAME "AMS_Slave10_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T18_NAME "AMS_Slave10_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T19_NAME "AMS_Slave10_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T20_NAME "AMS_Slave10_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T21_NAME "AMS_Slave10_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T22_NAME "AMS_Slave10_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG7_AMS_SLAVE10_T23_NAME "AMS_Slave10_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T24_NAME "AMS_Slave10_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T25_NAME "AMS_Slave10_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T26_NAME "AMS_Slave10_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T27_NAME "AMS_Slave10_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T28_NAME "AMS_Slave10_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T29_NAME "AMS_Slave10_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T30_NAME "AMS_Slave10_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_LOG8_AMS_SLAVE10_T31_NAME "AMS_Slave10_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_AMS_SLAVE11_V0_NAME "AMS_Slave11_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_AMS_SLAVE11_V1_NAME "AMS_Slave11_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_AMS_SLAVE11_V2_NAME "AMS_Slave11_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG0_AMS_SLAVE11_V3_NAME "AMS_Slave11_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_AMS_SLAVE11_V4_NAME "AMS_Slave11_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_AMS_SLAVE11_V5_NAME "AMS_Slave11_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_AMS_SLAVE11_V6_NAME "AMS_Slave11_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG1_AMS_SLAVE11_V7_NAME "AMS_Slave11_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_AMS_SLAVE11_V8_NAME "AMS_Slave11_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_AMS_SLAVE11_V9_NAME "AMS_Slave11_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_AMS_SLAVE11_V10_NAME "AMS_Slave11_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG2_AMS_SLAVE11_V11_NAME "AMS_Slave11_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_AMS_SLAVE11_V12_NAME "AMS_Slave11_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_AMS_SLAVE11_V13_NAME "AMS_Slave11_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_AMS_SLAVE11_V14_NAME "AMS_Slave11_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG3_AMS_SLAVE11_V15_NAME "AMS_Slave11_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG4_AMS_SLAVE11_V16_NAME "AMS_Slave11_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG4_AMS_SLAVE11_FAILED_SENSORS_NAME "AMS_Slave11_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T0_NAME "AMS_Slave11_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T1_NAME "AMS_Slave11_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T2_NAME "AMS_Slave11_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T3_NAME "AMS_Slave11_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T4_NAME "AMS_Slave11_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T5_NAME "AMS_Slave11_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T6_NAME "AMS_Slave11_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG5_AMS_SLAVE11_T7_NAME "AMS_Slave11_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T8_NAME "AMS_Slave11_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T9_NAME "AMS_Slave11_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T10_NAME "AMS_Slave11_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T11_NAME "AMS_Slave11_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T12_NAME "AMS_Slave11_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T13_NAME "AMS_Slave11_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T14_NAME "AMS_Slave11_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG6_AMS_SLAVE11_T15_NAME "AMS_Slave11_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T16_NAME "AMS_Slave11_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T17_NAME "AMS_Slave11_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T18_NAME "AMS_Slave11_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T19_NAME "AMS_Slave11_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T20_NAME "AMS_Slave11_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T21_NAME "AMS_Slave11_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T22_NAME "AMS_Slave11_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG7_AMS_SLAVE11_T23_NAME "AMS_Slave11_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T24_NAME "AMS_Slave11_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T25_NAME "AMS_Slave11_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T26_NAME "AMS_Slave11_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T27_NAME "AMS_Slave11_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T28_NAME "AMS_Slave11_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T29_NAME "AMS_Slave11_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T30_NAME "AMS_Slave11_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_LOG8_AMS_SLAVE11_T31_NAME "AMS_Slave11_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_AMS_SLAVE12_V0_NAME "AMS_Slave12_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_AMS_SLAVE12_V1_NAME "AMS_Slave12_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_AMS_SLAVE12_V2_NAME "AMS_Slave12_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG0_AMS_SLAVE12_V3_NAME "AMS_Slave12_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_AMS_SLAVE12_V4_NAME "AMS_Slave12_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_AMS_SLAVE12_V5_NAME "AMS_Slave12_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_AMS_SLAVE12_V6_NAME "AMS_Slave12_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG1_AMS_SLAVE12_V7_NAME "AMS_Slave12_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_AMS_SLAVE12_V8_NAME "AMS_Slave12_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_AMS_SLAVE12_V9_NAME "AMS_Slave12_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_AMS_SLAVE12_V10_NAME "AMS_Slave12_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG2_AMS_SLAVE12_V11_NAME "AMS_Slave12_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_AMS_SLAVE12_V12_NAME "AMS_Slave12_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_AMS_SLAVE12_V13_NAME "AMS_Slave12_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_AMS_SLAVE12_V14_NAME "AMS_Slave12_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG3_AMS_SLAVE12_V15_NAME "AMS_Slave12_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG4_AMS_SLAVE12_V16_NAME "AMS_Slave12_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG4_AMS_SLAVE12_FAILED_SENSORS_NAME "AMS_Slave12_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T0_NAME "AMS_Slave12_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T1_NAME "AMS_Slave12_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T2_NAME "AMS_Slave12_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T3_NAME "AMS_Slave12_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T4_NAME "AMS_Slave12_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T5_NAME "AMS_Slave12_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T6_NAME "AMS_Slave12_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG5_AMS_SLAVE12_T7_NAME "AMS_Slave12_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T8_NAME "AMS_Slave12_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T9_NAME "AMS_Slave12_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T10_NAME "AMS_Slave12_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T11_NAME "AMS_Slave12_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T12_NAME "AMS_Slave12_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T13_NAME "AMS_Slave12_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T14_NAME "AMS_Slave12_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG6_AMS_SLAVE12_T15_NAME "AMS_Slave12_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T16_NAME "AMS_Slave12_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T17_NAME "AMS_Slave12_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T18_NAME "AMS_Slave12_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T19_NAME "AMS_Slave12_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T20_NAME "AMS_Slave12_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T21_NAME "AMS_Slave12_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T22_NAME "AMS_Slave12_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG7_AMS_SLAVE12_T23_NAME "AMS_Slave12_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T24_NAME "AMS_Slave12_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T25_NAME "AMS_Slave12_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T26_NAME "AMS_Slave12_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T27_NAME "AMS_Slave12_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T28_NAME "AMS_Slave12_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T29_NAME "AMS_Slave12_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T30_NAME "AMS_Slave12_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_LOG8_AMS_SLAVE12_T31_NAME "AMS_Slave12_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_AMS_SLAVE13_V0_NAME "AMS_Slave13_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_AMS_SLAVE13_V1_NAME "AMS_Slave13_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_AMS_SLAVE13_V2_NAME "AMS_Slave13_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG0_AMS_SLAVE13_V3_NAME "AMS_Slave13_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_AMS_SLAVE13_V4_NAME "AMS_Slave13_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_AMS_SLAVE13_V5_NAME "AMS_Slave13_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_AMS_SLAVE13_V6_NAME "AMS_Slave13_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG1_AMS_SLAVE13_V7_NAME "AMS_Slave13_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_AMS_SLAVE13_V8_NAME "AMS_Slave13_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_AMS_SLAVE13_V9_NAME "AMS_Slave13_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_AMS_SLAVE13_V10_NAME "AMS_Slave13_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG2_AMS_SLAVE13_V11_NAME "AMS_Slave13_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_AMS_SLAVE13_V12_NAME "AMS_Slave13_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_AMS_SLAVE13_V13_NAME "AMS_Slave13_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_AMS_SLAVE13_V14_NAME "AMS_Slave13_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG3_AMS_SLAVE13_V15_NAME "AMS_Slave13_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG4_AMS_SLAVE13_V16_NAME "AMS_Slave13_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG4_AMS_SLAVE13_FAILED_SENSORS_NAME "AMS_Slave13_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T0_NAME "AMS_Slave13_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T1_NAME "AMS_Slave13_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T2_NAME "AMS_Slave13_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T3_NAME "AMS_Slave13_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T4_NAME "AMS_Slave13_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T5_NAME "AMS_Slave13_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T6_NAME "AMS_Slave13_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG5_AMS_SLAVE13_T7_NAME "AMS_Slave13_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T8_NAME "AMS_Slave13_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T9_NAME "AMS_Slave13_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T10_NAME "AMS_Slave13_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T11_NAME "AMS_Slave13_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T12_NAME "AMS_Slave13_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T13_NAME "AMS_Slave13_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T14_NAME "AMS_Slave13_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG6_AMS_SLAVE13_T15_NAME "AMS_Slave13_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T16_NAME "AMS_Slave13_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T17_NAME "AMS_Slave13_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T18_NAME "AMS_Slave13_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T19_NAME "AMS_Slave13_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T20_NAME "AMS_Slave13_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T21_NAME "AMS_Slave13_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T22_NAME "AMS_Slave13_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG7_AMS_SLAVE13_T23_NAME "AMS_Slave13_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T24_NAME "AMS_Slave13_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T25_NAME "AMS_Slave13_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T26_NAME "AMS_Slave13_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T27_NAME "AMS_Slave13_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T28_NAME "AMS_Slave13_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T29_NAME "AMS_Slave13_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T30_NAME "AMS_Slave13_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_LOG8_AMS_SLAVE13_T31_NAME "AMS_Slave13_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_AMS_SLAVE14_V0_NAME "AMS_Slave14_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_AMS_SLAVE14_V1_NAME "AMS_Slave14_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_AMS_SLAVE14_V2_NAME "AMS_Slave14_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG0_AMS_SLAVE14_V3_NAME "AMS_Slave14_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_AMS_SLAVE14_V4_NAME "AMS_Slave14_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_AMS_SLAVE14_V5_NAME "AMS_Slave14_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_AMS_SLAVE14_V6_NAME "AMS_Slave14_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG1_AMS_SLAVE14_V7_NAME "AMS_Slave14_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_AMS_SLAVE14_V8_NAME "AMS_Slave14_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_AMS_SLAVE14_V9_NAME "AMS_Slave14_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_AMS_SLAVE14_V10_NAME "AMS_Slave14_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG2_AMS_SLAVE14_V11_NAME "AMS_Slave14_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_AMS_SLAVE14_V12_NAME "AMS_Slave14_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_AMS_SLAVE14_V13_NAME "AMS_Slave14_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_AMS_SLAVE14_V14_NAME "AMS_Slave14_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG3_AMS_SLAVE14_V15_NAME "AMS_Slave14_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG4_AMS_SLAVE14_V16_NAME "AMS_Slave14_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG4_AMS_SLAVE14_FAILED_SENSORS_NAME "AMS_Slave14_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T0_NAME "AMS_Slave14_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T1_NAME "AMS_Slave14_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T2_NAME "AMS_Slave14_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T3_NAME "AMS_Slave14_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T4_NAME "AMS_Slave14_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T5_NAME "AMS_Slave14_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T6_NAME "AMS_Slave14_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG5_AMS_SLAVE14_T7_NAME "AMS_Slave14_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T8_NAME "AMS_Slave14_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T9_NAME "AMS_Slave14_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T10_NAME "AMS_Slave14_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T11_NAME "AMS_Slave14_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T12_NAME "AMS_Slave14_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T13_NAME "AMS_Slave14_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T14_NAME "AMS_Slave14_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG6_AMS_SLAVE14_T15_NAME "AMS_Slave14_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T16_NAME "AMS_Slave14_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T17_NAME "AMS_Slave14_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T18_NAME "AMS_Slave14_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T19_NAME "AMS_Slave14_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T20_NAME "AMS_Slave14_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T21_NAME "AMS_Slave14_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T22_NAME "AMS_Slave14_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG7_AMS_SLAVE14_T23_NAME "AMS_Slave14_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T24_NAME "AMS_Slave14_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T25_NAME "AMS_Slave14_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T26_NAME "AMS_Slave14_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T27_NAME "AMS_Slave14_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T28_NAME "AMS_Slave14_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T29_NAME "AMS_Slave14_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T30_NAME "AMS_Slave14_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_LOG8_AMS_SLAVE14_T31_NAME "AMS_Slave14_T31"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_AMS_SLAVE15_V0_NAME "AMS_Slave15_V0"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_AMS_SLAVE15_V1_NAME "AMS_Slave15_V1"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_AMS_SLAVE15_V2_NAME "AMS_Slave15_V2"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG0_AMS_SLAVE15_V3_NAME "AMS_Slave15_V3"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_AMS_SLAVE15_V4_NAME "AMS_Slave15_V4"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_AMS_SLAVE15_V5_NAME "AMS_Slave15_V5"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_AMS_SLAVE15_V6_NAME "AMS_Slave15_V6"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG1_AMS_SLAVE15_V7_NAME "AMS_Slave15_V7"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_AMS_SLAVE15_V8_NAME "AMS_Slave15_V8"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_AMS_SLAVE15_V9_NAME "AMS_Slave15_V9"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_AMS_SLAVE15_V10_NAME "AMS_Slave15_V10"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG2_AMS_SLAVE15_V11_NAME "AMS_Slave15_V11"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_AMS_SLAVE15_V12_NAME "AMS_Slave15_V12"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_AMS_SLAVE15_V13_NAME "AMS_Slave15_V13"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_AMS_SLAVE15_V14_NAME "AMS_Slave15_V14"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG3_AMS_SLAVE15_V15_NAME "AMS_Slave15_V15"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG4_AMS_SLAVE15_V16_NAME "AMS_Slave15_V16"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG4_AMS_SLAVE15_FAILED_SENSORS_NAME "AMS_Slave15_FailedSensors"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T0_NAME "AMS_Slave15_T0"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T1_NAME "AMS_Slave15_T1"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T2_NAME "AMS_Slave15_T2"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T3_NAME "AMS_Slave15_T3"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T4_NAME "AMS_Slave15_T4"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T5_NAME "AMS_Slave15_T5"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T6_NAME "AMS_Slave15_T6"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG5_AMS_SLAVE15_T7_NAME "AMS_Slave15_T7"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T8_NAME "AMS_Slave15_T8"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T9_NAME "AMS_Slave15_T9"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T10_NAME "AMS_Slave15_T10"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T11_NAME "AMS_Slave15_T11"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T12_NAME "AMS_Slave15_T12"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T13_NAME "AMS_Slave15_T13"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T14_NAME "AMS_Slave15_T14"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG6_AMS_SLAVE15_T15_NAME "AMS_Slave15_T15"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T16_NAME "AMS_Slave15_T16"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T17_NAME "AMS_Slave15_T17"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T18_NAME "AMS_Slave15_T18"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T19_NAME "AMS_Slave15_T19"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T20_NAME "AMS_Slave15_T20"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T21_NAME "AMS_Slave15_T21"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T22_NAME "AMS_Slave15_T22"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG7_AMS_SLAVE15_T23_NAME "AMS_Slave15_T23"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T24_NAME "AMS_Slave15_T24"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T25_NAME "AMS_Slave15_T25"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T26_NAME "AMS_Slave15_T26"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T27_NAME "AMS_Slave15_T27"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T28_NAME "AMS_Slave15_T28"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T29_NAME "AMS_Slave15_T29"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T30_NAME "AMS_Slave15_T30"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_LOG8_AMS_SLAVE15_T31_NAME "AMS_Slave15_T31"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_AS_MISSION_NAME "Jetson_AS_Mission"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_AS_STATE_NAME "Jetson_AS_State"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_POWER_OFF_NAME "Jetson_Power_Off"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_RESET_NAME "Jetson_Reset"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_SPEED_NAME "Jetson_Speed"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_SPEED_X_SENS_NAME "Jetson_Speed_XSens"
+#define CAN1__MAIN_FT24_JETSON_RX_JETSON_ALLOW_TORQUE_NAME "Jetson_AllowTorque"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE15_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE14_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE13_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE12_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE11_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE10_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE9_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE8_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE7_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE6_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE5_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE4_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE3_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE2_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE1_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_ABX_MISC_ABX_DRIVER_PROTOCOL_NAME "ABX_DriverProtocol"
+#define CAN1__MAIN_FT24_ABX_MISC_ABX_DISTANCE_SESSION_NAME "ABX_Distance_session"
+#define CAN1__MAIN_FT24_ABX_MISC_ABX_DISTANCE_TOTAL_NAME "ABX_Distance_total"
+#define CAN1__MAIN_FT24_ABX_MISC_ABX_LV_SO_C_NAME "ABX_LV_SoC"
+#define CAN1__MAIN_FT24_ABX_MISC_ABX_LV_VOLTAGE_NAME "ABX_LV_Voltage"
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_KIND_NAME "AMS_Error_Kind"
+#define CAN1__MAIN_FT24_AMS_ERROR_AMS_ERROR_ARG_NAME "AMS_Error_Arg"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_ABX_CS_T_INV_L_NAME "ABX_CS_T_InvL"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_ABX_CS_T_INV_R_NAME "ABX_CS_T_InvR"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_ABX_CS_T_MOT_L_NAME "ABX_CS_T_MotL"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_INTERNAL_ABX_CS_T_MOT_R_NAME "ABX_CS_T_MotR"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_ABX_CS_P_ACC_IN_NAME "ABX_CS_P_AccIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_ABX_CS_P_ACC_OUT_NAME "ABX_CS_P_AccOut"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_ABX_CS_T_ACC_IN_NAME "ABX_CS_T_AccIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_ACC_ABX_CS_T_ACC_OUT_NAME "ABX_CS_T_AccOut"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_P_INV_IN_NAME "ABX_CS_P_InvIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_P_MOT_L_IN_NAME "ABX_CS_P_MotLIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_P_RAD_IN_NAME "ABX_CS_P_RadIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_P_MOT_R_IN_NAME "ABX_CS_P_MotRIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_T_INV_IN_NAME "ABX_CS_T_InvIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_T_MOT_IN_NAME "ABX_CS_T_MotIn"
+#define CAN1__MAIN_FT24_ABX_COOLING_SYS_MOT_INV_ABX_CS_T_RAD_IN_NAME "ABX_CS_T_RadIn"
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_ABX_BRAKE_T_FL_NAME "ABX_BrakeT_FL"
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_ABX_BRAKE_T_FR_NAME "ABX_BrakeT_FR"
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_ABX_BRAKE_T_RL_NAME "ABX_BrakeT_RL"
+#define CAN1__MAIN_FT24_ABX_BRAKE_T_ABX_BRAKE_T_RR_NAME "ABX_BrakeT_RR"
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_ABX_WHEELSPEED_FL_NAME "ABX_Wheelspeed_FL"
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_ABX_WHEELSPEED_FR_NAME "ABX_Wheelspeed_FR"
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_ABX_WHEELSPEED_RL_NAME "ABX_Wheelspeed_RL"
+#define CAN1__MAIN_FT24_ABX_WHEELSPEED_ABX_WHEELSPEED_RR_NAME "ABX_Wheelspeed_RR"
+#define CAN1__MAIN_FT24_ABX_DAMPERS_ABX_DAMPER_HEAVE_F_NAME "ABX_DamperHeave_F"
+#define CAN1__MAIN_FT24_ABX_DAMPERS_ABX_DAMPER_ROLL_F_NAME "ABX_DamperRoll_F"
+#define CAN1__MAIN_FT24_ABX_DAMPERS_ABX_DAMPER_HEAVE_R_NAME "ABX_DamperHeave_R"
+#define CAN1__MAIN_FT24_ABX_DAMPERS_ABX_DAMPER_ROLL_R_NAME "ABX_DamperRoll_R"
+#define CAN1__MAIN_FT24_ABX_TIMINGS_ABX_LAPTIME_BEST_NAME "ABX_Laptime_best"
+#define CAN1__MAIN_FT24_ABX_TIMINGS_ABX_LAPTIME_LAST_NAME "ABX_Laptime_last"
+#define CAN1__MAIN_FT24_ABX_TIMINGS_ABX_SECTORTIME_BEST_NAME "ABX_Sectortime_best"
+#define CAN1__MAIN_FT24_ABX_TIMINGS_ABX_SECTORTIME_LAST_NAME "ABX_Sectortime_last"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_APPS_PERCENT_NAME "ABX_APPS_percent"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_BRAKE_P_F_NAME "ABX_BrakeP_F"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_BRAKE_P_R_NAME "ABX_BrakeP_R"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_STEERING_ANGLE_NAME "ABX_Steering_Angle"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_SPEED_NAME "ABX_Speed"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_LAPCOUNTER_NAME "ABX_Lapcounter"
+#define CAN1__MAIN_FT24_ABX_DRIVER_ABX_SECTORCOUNTER_NAME "ABX_Sectorcounter"
+#define CAN1__MAIN_FT24_TTS_CONFIG_TTS_NEW_ID_NAME "TTS_NewID"
+#define CAN1__MAIN_FT24_TTS_RR_TTS_RR_INNER_NAME "TTS_RR_Inner"
+#define CAN1__MAIN_FT24_TTS_RR_TTS_RR_CENTER_IN_NAME "TTS_RR_CenterIn"
+#define CAN1__MAIN_FT24_TTS_RR_TTS_RR_CENTER_NAME "TTS_RR_Center"
+#define CAN1__MAIN_FT24_TTS_RR_TTS_RR_CENTER_OUT_NAME "TTS_RR_CenterOut"
+#define CAN1__MAIN_FT24_TTS_RR_TTS_RR_OUTER_NAME "TTS_RR_Outer"
+#define CAN1__MAIN_FT24_TTS_RL_TTS_RL_OUTER_NAME "TTS_RL_Outer"
+#define CAN1__MAIN_FT24_TTS_RL_TTS_RL_CENTER_OUT_NAME "TTS_RL_CenterOut"
+#define CAN1__MAIN_FT24_TTS_RL_TTS_RL_CENTER_NAME "TTS_RL_Center"
+#define CAN1__MAIN_FT24_TTS_RL_TTS_RL_CENTER_IN_NAME "TTS_RL_CenterIn"
+#define CAN1__MAIN_FT24_TTS_RL_TTS_RL_INNER_NAME "TTS_RL_Inner"
+#define CAN1__MAIN_FT24_TTS_FR_TTS_FR_INNER_NAME "TTS_FR_Inner"
+#define CAN1__MAIN_FT24_TTS_FR_TTS_FR_CENTER_IN_NAME "TTS_FR_CenterIn"
+#define CAN1__MAIN_FT24_TTS_FR_TTS_FR_CENTER_NAME "TTS_FR_Center"
+#define CAN1__MAIN_FT24_TTS_FR_TTS_FR_CENTER_OUT_NAME "TTS_FR_CenterOut"
+#define CAN1__MAIN_FT24_TTS_FR_TTS_FR_OUTER_NAME "TTS_FR_Outer"
+#define CAN1__MAIN_FT24_TTS_FL_TTS_FL_OUTER_NAME "TTS_FL_Outer"
+#define CAN1__MAIN_FT24_TTS_FL_TTS_FL_CENTER_OUT_NAME "TTS_FL_CenterOut"
+#define CAN1__MAIN_FT24_TTS_FL_TTS_FL_CENTER_NAME "TTS_FL_Center"
+#define CAN1__MAIN_FT24_TTS_FL_TTS_FL_CENTER_IN_NAME "TTS_FL_CenterIn"
+#define CAN1__MAIN_FT24_TTS_FL_TTS_FL_INNER_NAME "TTS_FL_Inner"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TYPE_NAME "STW_Param_Type"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_B_BAL_NAME "STW_Param_BBal"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_SLIPREF_NAME "STW_Param_SLIPREF"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_ASRP_NAME "STW_Param_ASRP"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_ASRON_NAME "STW_Param_ASRON"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_ASRI_NAME "STW_Param_ASRI"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_ENDU_POWER_LIMIT_NAME "STW_Param_EnduPowerLimit"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TEST3_NAME "STW_Param_Test3"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_TEST4_NAME "STW_Param_Test4"
+#define CAN1__MAIN_FT24_STW_PARAM_SET_STW_PARAM_MUMAX_NAME "STW_Param_MUMAX"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_AMS_SLAVE_STATUS_ERROR_NAME "AMS_SlaveStatus_Error"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_AMS_SLAVE_STATUS_ID_NAME "AMS_SlaveStatus_ID"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_AMS_SLAVE_STATUS_SO_C_NAME "AMS_SlaveStatus_SoC"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_AMS_SLAVE_STATUS_MIN_CELL_VOLT_NAME "AMS_SlaveStatus_MinCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_AMS_SLAVE_STATUS_MAX_CELL_VOLT_NAME "AMS_SlaveStatus_MaxCellVolt"
+#define CAN1__MAIN_FT24_AMS_SLAVE0_STATUS_AMS_SLAVE_STATUS_MAX_TEMP_NAME "AMS_SlaveStatus_MaxTemp"
+#define CAN1__MAIN_FT24_SSU_MESSAGE_SSU_AIR_PRESSURE_NAME "SSU_AirPressure"
+#define CAN1__MAIN_FT24_SSU_MESSAGE_SSU_AIR_TEMP_NAME "SSU_AirTemp"
+#define CAN1__MAIN_FT24_AMS_STATUS_AMS_STATE_NAME "AMS_State"
+#define CAN1__MAIN_FT24_AMS_STATUS_SDC_CLOSED_NAME "SDC_Closed"
+#define CAN1__MAIN_FT24_AMS_STATUS_SOC_NAME "SOC"
+#define CAN1__MAIN_FT24_AMS_STATUS_MIN_CELL_VOLT_NAME "Min_cell_volt"
+#define CAN1__MAIN_FT24_AMS_STATUS_MAX_CELL_TEMP_NAME "Max_cell_temp"
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_SLAVE_ID_NAME "AMS_SlavePanic_SlaveID"
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_KIND_NAME "AMS_SlavePanic_Kind"
+#define CAN1__MAIN_FT24_AMS_SLAVE_PANIC_AMS_SLAVE_PANIC_ARG_NAME "AMS_SlavePanic_Arg"
+#define CAN1__MAIN_FT24_AMS_IN_TS_ACTIVATE_NAME "TS_activate"
+#define CAN1__MAIN_FT24_AMS_IN_INVERTERS_DISCHARGED_NAME "Inverters_discharged"
+#define CAN1__MAIN_FT24_AMS_IN_LAP_NUMBER_NAME "Lap_Number"
+#define CAN1__MAIN_FT24_SHUNT_CURRENT_SHUNT_CURRENT_NAME "Shunt_Current"
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE1_SHUNT_VOLTAGE1_NAME "Shunt_Voltage1"
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE2_SHUNT_VOLTAGE2_NAME "Shunt_Voltage2"
+#define CAN1__MAIN_FT24_SHUNT_VOLTAGE3_SHUNT_VOLTAGE3_NAME "Shunt_Voltage3"
+#define CAN1__MAIN_FT24_SHUNT_TEMPERATURE_SHUNT_TEMPERATURE_NAME "Shunt_Temperature"
+#define CAN1__MAIN_FT24_SDCL_TX_ASMS_STATE_NAME "asms_state"
+#define CAN1__MAIN_FT24_SDCL_TX_SDC_STATE_1_NAME "sdc_state_1"
+#define CAN1__MAIN_FT24_SDCL_TX_SDC_STATE_2_NAME "sdc_state_2"
+#define CAN1__MAIN_FT24_SDCL_TX_SDC_STATE_3_NAME "sdc_state_3"
+#define CAN1__MAIN_FT24_SDCL_TX_HEARTBEAT_OK_NAME "heartbeat_ok"
+#define CAN1__MAIN_FT24_SDCL_TX_SDCL_SDC_READY_NAME "sdcl_sdc_ready"
+#define CAN1__MAIN_FT24_SDCL_TX_TS_START_MUXED_NAME "ts_start_muxed"
+#define CAN1__MAIN_FT24_SDCL_TX_LATCH_INIT_OPEN_NAME "latch_init_open"
+#define CAN1__MAIN_FT24_SDCL_TX_LATCH_CLOSED_NAME "latch_closed"
+#define CAN1__MAIN_FT24_SDCL_TX_LATCH_REOPENED_NAME "latch_reopened"
+#define CAN1__MAIN_FT24_SDCL_TX_AS_MISSION_NAME "as_mission"
+#define CAN1__MAIN_FT24_SDCL_RX_AS_CLOSE_SDC_NAME "as_close_sdc"
+#define CAN1__MAIN_FT24_SDCL_RX_SDCL_HEARTBEAT_NAME "sdcl_heartbeat"
+#define CAN1__MAIN_FT24_SDCL_RX_ASB_ERROR_NAME "asb_error"
+#define CAN1__MAIN_FT24_SDCL_RX_AS_MISSION_NAME "as_mission"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_INVERTER_RX_NAME "PDU_inverter_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_MODE_VALVE_2_RX_NAME "PDU_mode_valve_2_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_EBS_VALVE_2_RX_NAME "PDU_ebs_valve_2_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_SHUTDOWN_CIRCUIT_RX_NAME "PDU_shutdown_circuit_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_ALWAYSON_RX_NAME "PDU_alwayson_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_MISC_RX_NAME "PDU_misc_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_SERVO_RX_NAME "PDU_servo_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_LED1_RX_NAME "PDU_led1_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_LED2_RX_NAME "PDU_led2_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_LED3_RX_NAME "PDU_led3_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_SENSORBOX_RX_NAME "PDU_sensorbox_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_SERVICE_BRAKE_RX_NAME "PDU_service_brake_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_EBS_VALVE_1_RX_NAME "PDU_ebs_valve_1_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_STEERING_RX_NAME "PDU_steering_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_MODE_VALVE_1_RX_NAME "PDU_mode_valve_1_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_PWM_FANS_RX_NAME "PDU_PWM_fans_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_PWM_AGGREGAT_RX_NAME "PDU_PWM_aggregat_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_PWM_PUMP_RX_NAME "PDU_PWM_pump_rx"
+#define CAN1__MAIN_FT24_PDU_COMMAND_PDU_CHECKSUM_RX_NAME "PDU_checksum_rx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_INVERTER_TX_NAME "PDU_inverter_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_MODE_VALVE_2_TX_NAME "PDU_mode_valve_2_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_EVS_VALVE_2_TX_NAME "PDU_evs_valve_2_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_SHUTDOWN_CIRCUIT_TX_NAME "PDU_shutdown_circuit_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_ALWAYSON_TX_NAME "PDU_alwayson_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_MISC_TX_NAME "PDU_misc_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_SERVO_TX_NAME "PDU_servo_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_LED1_TX_NAME "PDU_led1_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_LED2_TX_NAME "PDU_led2_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_LED3_TX_NAME "PDU_led3_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_SENSORBOX_TX_NAME "PDU_sensorbox_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_SERVICE_BRAKE_TX_NAME "PDU_service_brake_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_EBS_VALVE_1_TX_NAME "PDU_ebs_valve_1_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_STEERING_TX_NAME "PDU_steering_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_MODE_VALVE_1_TX_NAME "PDU_mode_valve_1_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_PWM_FANS_TX_NAME "PDU_PWM_fans_tx"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_PWM_AGGREGAT_NAME "PDU_PWM_aggregat"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_PWM_PUMP_NAME "PDU_PWM_pump"
+#define CAN1__MAIN_FT24_PDU_RESPONSE_PDU_CHECKSUM_TX_NAME "PDU_checksum_tx"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_POWERSUPPLY_LESS_8V_NAME "pdm_powersupply_less_8v"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_POWERSUPPLY_GREATER_32V_NAME "pdm_powersupply_greater_32v"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_CANBUS_TIMEOUT_NAME "pdm_canbus_timeout"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_CANBUS_STARTUPMISSING_NAME "pdm_canbus_startupmissing"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_CANBUS_STATEWARNING_NAME "pdm_canbus_statewarning"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_ANALOGINPUT_MIDDLEPOSITION_NAME "pdm_analoginput_middleposition"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_ANALOGINPUT_CABLEBREAK_NAME "pdm_analoginput_cablebreak"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_ANALOGINPUT_SHORTCIRCUIT_NAME "pdm_analoginput_shortcircuit"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_ANALOGINPUT_CURRENTOVERLOAD_NAME "pdm_analoginput_currentoverload"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_TEMPERATURE_WARNING_NAME "pdm_temperature_warning"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_TEMPERATURE_SHUTDOWN_NAME "pdm_temperature_shutdown"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_OUTPUT1_CONTROLLERRANGE_NAME "pdm_output1_controllerrange"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_OUTPUT2_CONTROLLERRANGE_NAME "pdm_output2_controllerrange"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_OUTPUT1_CABLEBREAK_NAME "pdm_output1_cablebreak"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_OUTPUT2_CABLEBREAK_NAME "pdm_output2_cablebreak"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_OUTPUT1_SHORTCIRCUIT_NAME "pdm_output1_shortcircuit"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_OUTPUT2_SHORTCIRCUIT_NAME "pdm_output2_shortcircuit"
+#define CAN1__MAIN_FT24_TX_PDO_PDM_ANALOGINPUT_NAME "PDM_analoginput"
+#define CAN1__MAIN_FT24_X_SENS_WARNING_WARNING_CODE_NAME "WarningCode"
+#define CAN1__MAIN_FT24_X_SENS_SAMPLE_TIME_TIMESTAMP_NAME "Timestamp"
+#define CAN1__MAIN_FT24_X_SENS_GROUP_COUNTER_COUNTER_NAME "Counter"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_HAVE_GNSS_TIME_PULSE_NAME "HaveGnssTimePulse"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RTK_STATUS_NAME "RtkStatus"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_FILTER_MODE_NAME "FilterMode"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_Z_NAME "ClipMagZ"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_RETRANSMITTED_NAME "Retransmitted"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIPPING_DETECTED_NAME "ClippingDetected"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_INTERPOLATED_NAME "Interpolated"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SYNC_IN_NAME "SyncIn"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SYNC_OUT_NAME "SyncOut"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_X_NAME "ClipAccX"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_Y_NAME "ClipAccY"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_ACC_Z_NAME "ClipAccZ"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_X_NAME "ClipGyrX"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_Y_NAME "ClipGyrY"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_GYR_Z_NAME "ClipGyrZ"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_X_NAME "ClipMagX"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_CLIP_MAG_Y_NAME "ClipMagY"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_SELF_TEST_OK_NAME "SelfTestOk"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_ORIENTATION_VALID_NAME "OrientationValid"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_GPS_VALID_NAME "GpsValid"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_NO_ROTATION_NAME "NoRotation"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_REPRESENTATIVE_MOTION_NAME "RepresentativeMotion"
+#define CAN1__MAIN_FT24_X_SENS_STATUS_WORD_EXTERNAL_CLOCK_SYNCED_NAME "ExternalClockSynced"
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_X_SENS_GYR_X_NAME "XSens_gyrX"
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_X_SENS_GYR_Y_NAME "XSens_gyrY"
+#define CAN1__MAIN_FT24_X_SENS_RATE_OF_TURN_X_SENS_GYR_Z_NAME "XSens_gyrZ"
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_X_SENS_ACC_X_NAME "XSens_accX"
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_X_SENS_ACC_Y_NAME "XSens_accY"
+#define CAN1__MAIN_FT24_X_SENS_ACCELERATION_X_SENS_ACC_Z_NAME "XSens_accZ"
+#define CAN1__MAIN_FT24_X_SENS_LONG_LAT_LATITUDE_NAME "latitude"
+#define CAN1__MAIN_FT24_X_SENS_LONG_LAT_LONGITUDE_NAME "longitude"
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_VEL_X_NAME "velX"
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_VEL_Y_NAME "velY"
+#define CAN1__MAIN_FT24_X_SENS_VELOCITY_VEL_Z_NAME "velZ"
+#define CAN1__MAIN_FT24_AS_MISSION_FB_MISSION_SELECTION_NAME "Mission_selection"
+#define CAN1__MAIN_FT24_STW_MISSION_SELECTED_MISSION_SELECTION_NAME "Mission_selection"
+#define CAN1__MAIN_FT24_EPSC_OUT_EPSC_MEASURED_STEERING_ANGLE_NAME "EPSC_measured_steering_angle"
+#define CAN1__MAIN_FT24_EPSC_OUT_EPSC_MEASURED_CURRENT_NAME "EPSC_measured_current"
+#define CAN1__MAIN_FT24_EPSC_OUT_EPSC_MEASURED_VOLTAGE_NAME "EPSC_measured_voltage"
+#define CAN1__MAIN_FT24_EPSC_OUT_EPSC_MEASURED_RPM_NAME "EPSC_measured_rpm"
+#define CAN1__MAIN_FT24_EPSC_OUT_EPSC_MEASURED_TEMPERATURE_NAME "EPSC_measured_temperature"
+#define CAN1__MAIN_FT24_EPSC_OUT_EPSC_MEASURED_INTERNAL_TEMP_NAME "EPSC_measured_internal_temp"
+#define CAN1__MAIN_FT24_EPSC_STEERING_IN_EPSC_DESIRED_STEERING_ANGLE_NAME "EPSC_desired_steering_angle"
+#define CAN1__MAIN_FT24_STW_BUTTONS_STW_BUTTON_LEFT_NAME "STW_button_left"
+#define CAN1__MAIN_FT24_STW_BUTTONS_STW_BUTTON_RIGHT_NAME "STW_button_right"
+#define CAN1__MAIN_FT24_STW_BUTTONS_STW_BUTTON_R2_D_NAME "STW_button_R2D"
+#define CAN1__MAIN_FT24_STW_BUTTONS_STW_BUTTON_ENTER_NAME "STW_button_Enter"
+#define CAN1__MAIN_FT24_STW_STATUS_AS_STATE_STW_NAME "AS_State_STW"
+#define CAN1__MAIN_FT24_STW_STATUS_R2_D_PROGRESS_NAME "R2D_Progress"
+#define CAN1__MAIN_FT24_STW_STATUS_INV_L_READY_NAME "InvL_ready"
+#define CAN1__MAIN_FT24_STW_STATUS_INV_R_READY_NAME "InvR_ready"
+#define CAN1__MAIN_FT24_STW_STATUS_SDC_BFL_NAME "SDC_BFL"
+#define CAN1__MAIN_FT24_STW_STATUS_SDC_BRL_NAME "SDC_BRL"
+#define CAN1__MAIN_FT24_STW_STATUS_SDC_ACC_NAME "SDC_ACC"
+#define CAN1__MAIN_FT24_STW_STATUS_SDC_HVB_NAME "SDC_HVB"
+#define CAN1__MAIN_FT24_STW_STATUS_LAP_COUNT_NAME "Lap_Count"
+#define CAN1__MAIN_FT24_STW_STATUS_INI_CHK_STATE_NAME "iniChk_state"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_SDC_NAME "ERR_SDC"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_AMS_NAME "ERR_AMS"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_PDU_NAME "ERR_PDU"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_INI_CHK_NAME "ERR_IniChk"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_CON_MON_NAME "ERR_ConMon"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_SCS_NAME "ERR_SCS"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_S_BSPD_NAME "ERR_sBSPD"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_APP_SP_NAME "ERR_APPSp"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_AS_NAME "ERR_AS"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_ROS_NAME "ERR_ROS"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_RES_NAME "ERR_RES"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_INV_L_NAME "ERR_InvL"
+#define CAN1__MAIN_FT24_STW_STATUS_ERR_INV_R_NAME "ERR_InvR"
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_PDU_ALWAYSON_CURR_NAME "PDU_alwayson_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_PDU_MISC_CURR_NAME "PDU_misc_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_PDU_INVERTER_CURR_NAME "PDU_inverter_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_1_PDU_SHUTDOWN_CIRCUIT_CURR_NAME "PDU_shutdown_circuit_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_PDU_FANS_CURR_NAME "PDU_fans_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_PDU_PUMP_CURR_NAME "PDU_pump_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_PDU_AGGREGAT_CURR_NAME "PDU_aggregat_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_2_PDU_STEERING_CURR_NAME "PDU_steering_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_PDU_EBS_VALVE_1_CURR_NAME "PDU_ebs_valve_1_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_PDU_EBS_VALVE_2_CURR_NAME "PDU_ebs_valve_2_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_PDU_MODE_VALVE_1_CURR_NAME "PDU_mode_valve_1_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_3_PDU_MODE_VALVE_2_CURR_NAME "PDU_mode_valve_2_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_PDU_SENSORBOX_CURR_NAME "PDU_sensorbox_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_PDU_SERVICE_BRAKE_CURR_NAME "PDU_service_brake_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_PDU_SERVOS_CURR_NAME "PDU_servos_curr"
+#define CAN1__MAIN_FT24_PDU_CURRENT_4_PDU_SHUTDOWN_CIRCUIT_CURR_NAME "PDU_shutdown_circuit_curr"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_SHOULD_CALIBRATE_NAME "EPSC_should_calibrate"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_SHOULD_CHANGE_MODE_NAME "EPSC_should_change_mode"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_MODE_NAME "EPSC_mode"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_FLAG3_NAME "EPSC_flag3"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_FLAG4_NAME "EPSC_flag4"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_FLAG5_NAME "EPSC_flag5"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_FLAG6_NAME "EPSC_flag6"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_FLAG7_NAME "EPSC_flag7"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_KP_POS_NAME "EPSC_Kp_pos"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_KI_POS_NAME "EPSC_Ki_pos"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_KP_RPM_NAME "EPSC_Kp_rpm"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_KI_RPM_NAME "EPSC_Ki_rpm"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_KP_CURR_NAME "EPSC_Kp_curr"
+#define CAN1__MAIN_FT24_EPSC_CONFIG_IN_EPSC_KI_CURR_NAME "EPSC_Ki_curr"
+
+/**
+ * Signals in message ABX_ParamConfirm.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_param_confirm_t {
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t abx_param_confirm;
+};
+
+/**
+ * Signals in message ABX_Hydraulics.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_hydraulics_t {
+ /**
+ * Range: 0..4095 (0..409.5 bar)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_hyd_pa;
+
+ /**
+ * Range: 0..4095 (0..409.5 bar)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_hyd_pb;
+};
+
+/**
+ * Signals in message JetsonTX.
+ *
+ * Cycle Time: 100ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_jetson_tx_t {
+ /**
+ * Range: 0..1 (0..1 Bool)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_as_mission_complete;
+
+ /**
+ * Range: 0..1 (0..1 Bool)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_as_ok;
+
+ /**
+ * Range: 0..15 (0..15 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_lap_count;
+
+ /**
+ * Range: 0..255 (0..51 -)
+ * Scale: 0.2
+ * Offset: 0
+ */
+ uint8_t jetson_speed_target;
+
+ /**
+ * Range: -128..128 (-1..1 -)
+ * Scale: 0.00784313725490196
+ * Offset: 0
+ */
+ int8_t jetson_steering_angle;
+
+ /**
+ * Range: 0..255 (0..1 -)
+ * Scale: 0.00392156862745098
+ * Offset: 0
+ */
+ uint8_t jetson_brake_ratio;
+
+ /**
+ * Range: 0..255 (0..1 -)
+ * Scale: 0.00392156862745098
+ * Offset: 0
+ */
+ uint8_t jetson_torque_ratio;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_cones_all;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_cones_actual;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v3;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v7;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v11;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v15;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave0_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave0_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t7;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t15;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t23;
+};
+
+/**
+ * Signals in message AMS_Slave0_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave0_t31;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v3;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v7;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v11;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v15;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave1_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave1_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t7;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t15;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t23;
+};
+
+/**
+ * Signals in message AMS_Slave1_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave1_t31;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v3;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v7;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v11;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v15;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave2_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave2_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t7;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t15;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t23;
+};
+
+/**
+ * Signals in message AMS_Slave2_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave2_t31;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v3;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v7;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v11;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v15;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave3_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave3_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t7;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t15;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t23;
+};
+
+/**
+ * Signals in message AMS_Slave3_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave3_t31;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v3;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v7;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v11;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v15;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave4_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave4_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t7;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t15;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t23;
+};
+
+/**
+ * Signals in message AMS_Slave4_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave4_t31;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v3;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v7;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v11;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v15;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave5_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave5_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t7;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t15;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t23;
+};
+
+/**
+ * Signals in message AMS_Slave5_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave5_t31;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v3;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v7;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v11;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v15;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave6_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave6_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t7;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t15;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t23;
+};
+
+/**
+ * Signals in message AMS_Slave6_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave6_t31;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v3;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v7;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v11;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v15;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave7_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave7_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t7;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t15;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t23;
+};
+
+/**
+ * Signals in message AMS_Slave7_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave7_t31;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v3;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v7;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v11;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v15;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave8_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave8_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t7;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t15;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t23;
+};
+
+/**
+ * Signals in message AMS_Slave8_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave8_t31;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v3;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v7;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v11;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v15;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave9_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave9_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t7;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t15;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t23;
+};
+
+/**
+ * Signals in message AMS_Slave9_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave9_t31;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v3;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v7;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v11;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v15;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave10_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave10_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t7;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t15;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t23;
+};
+
+/**
+ * Signals in message AMS_Slave10_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave10_t31;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v3;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v7;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v11;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v15;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave11_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave11_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t7;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t15;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t23;
+};
+
+/**
+ * Signals in message AMS_Slave11_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave11_t31;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v3;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v7;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v11;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v15;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave12_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave12_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t7;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t15;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t23;
+};
+
+/**
+ * Signals in message AMS_Slave12_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave12_t31;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v3;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v7;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v11;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v15;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave13_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave13_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t7;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t15;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t23;
+};
+
+/**
+ * Signals in message AMS_Slave13_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave13_t31;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v3;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v7;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v11;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v15;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave14_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave14_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t7;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t15;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t23;
+};
+
+/**
+ * Signals in message AMS_Slave14_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave14_t31;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log0.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log0_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v0;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v1;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v2;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v3;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log1_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v4;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v5;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v6;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v7;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log2_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v8;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v9;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v10;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v11;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log3_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v12;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v13;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v14;
+
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v15;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log4_t {
+ /**
+ * Range: 0..65535 (0..6.5535 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave15_v16;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave15_failed_sensors;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log5.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log5_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t0;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t1;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t2;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t3;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t4;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t5;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t6;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t7;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log6.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log6_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t8;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t9;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t10;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t11;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t12;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t13;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t14;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t15;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log7.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log7_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t16;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t17;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t18;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t19;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t20;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t21;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t22;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t23;
+};
+
+/**
+ * Signals in message AMS_Slave15_Log8.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_log8_t {
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t24;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t25;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t26;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t27;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t28;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t29;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t30;
+
+ /**
+ * Range: -128..127 (-128..127 degC)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_slave15_t31;
+};
+
+/**
+ * Signals in message JetsonRX.
+ *
+ * Cycle Time: 50ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_jetson_rx_t {
+ /**
+ * AS Mission Selection
+ *
+ * Range: 0..7 (0..7 int)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_as_mission;
+
+ /**
+ * Range: 0..5 (0..5 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_as_state;
+
+ /**
+ * Range: 0..1 (0..1 bool)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_power_off;
+
+ /**
+ * Range: 0..1 (0..1 bool)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_reset;
+
+ /**
+ * Range: 0..255 (0..51 m/s)
+ * Scale: 0.2
+ * Offset: 0
+ */
+ uint8_t jetson_speed;
+
+ /**
+ * Range: 0..255 (0..51 m/s)
+ * Scale: 0.2
+ * Offset: 0
+ */
+ uint8_t jetson_speed_x_sens;
+
+ /**
+ * Range: 0..1 (0..1 bool)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t jetson_allow_torque;
+};
+
+/**
+ * Signals in message AMS_Slave15Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave15_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave14Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave14_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave13Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave13_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave12Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave12_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave11Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave11_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave10Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave10_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave9Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave9_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave8Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave8_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave7Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave7_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave6Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave6_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave5Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave5_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave4Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave4_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave3Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave3_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave2Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave2_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message AMS_Slave1Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave1_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message ABX_Misc.
+ *
+ * Cycle time: 1s
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_misc_t {
+ /**
+ * Range: 0..7 (0..7 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t abx_driver_protocol;
+
+ /**
+ * Range: 0..65535 (0..65535 m)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t abx_distance_session;
+
+ /**
+ * Range: 0..65535 (0..655.35 km)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_distance_total;
+
+ /**
+ * Range: 0..100 (0..100 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t abx_lv_so_c;
+
+ /**
+ * Range: 0..255 (0..15 V)
+ * Scale: 0.0588235294117647
+ * Offset: 0
+ */
+ uint8_t abx_lv_voltage;
+};
+
+/**
+ * Signals in message AMS_Error.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_error_t {
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_error_kind;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t ams_error_arg;
+};
+
+/**
+ * Signals in message ABX_CoolingSys_Internal.
+ *
+ * Cycle time: 100ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_cooling_sys_internal_t {
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_inv_l;
+
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_inv_r;
+
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_mot_l;
+
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_mot_r;
+};
+
+/**
+ * Signals in message ABX_CoolingSys_Acc.
+ *
+ * Cycle time: 100ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_cooling_sys_acc_t {
+ /**
+ * Range: 0..200 (0..4 bar)
+ * Scale: 0.02
+ * Offset: 0
+ */
+ uint8_t abx_cs_p_acc_in;
+
+ /**
+ * Range: 0..200 (0..4 bar)
+ * Scale: 0.02
+ * Offset: 0
+ */
+ uint8_t abx_cs_p_acc_out;
+
+ /**
+ * Range: 0..1023 (0..102.3 �C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_acc_in;
+
+ /**
+ * Range: 0..1023 (0..102.3 �C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_acc_out;
+};
+
+/**
+ * Signals in message ABX_CoolingSys_MotInv.
+ *
+ * Cycle time: 100ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_cooling_sys_mot_inv_t {
+ /**
+ * Range: 0..200 (0..4 bar)
+ * Scale: 0.02
+ * Offset: 0
+ */
+ uint8_t abx_cs_p_inv_in;
+
+ /**
+ * Range: 0..200 (0..4 bar)
+ * Scale: 0.02
+ * Offset: 0
+ */
+ uint8_t abx_cs_p_mot_l_in;
+
+ /**
+ * Range: 0..200 (0..4 bar)
+ * Scale: 0.02
+ * Offset: 0
+ */
+ uint8_t abx_cs_p_rad_in;
+
+ /**
+ * Range: 0..200 (0..4 bar)
+ * Scale: 0.02
+ * Offset: 0
+ */
+ uint8_t abx_cs_p_mot_r_in;
+
+ /**
+ * Range: 0..1023 (0..102.3 �C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_inv_in;
+
+ /**
+ * Range: 0..1023 (0..102.3 �C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_mot_in;
+
+ /**
+ * Range: 0..1023 (0..102.3 �C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_cs_t_rad_in;
+};
+
+/**
+ * Signals in message ABX_BrakeT.
+ *
+ * Cycle time: 100ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_brake_t_t {
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_brake_t_fl;
+
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_brake_t_fr;
+
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_brake_t_rl;
+
+ /**
+ * Range: 0..65535 (0..655.35 �C)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_brake_t_rr;
+};
+
+/**
+ * Signals in message ABX_Wheelspeed.
+ *
+ * Cycle time: 10ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_wheelspeed_t {
+ /**
+ * Range: -32768..32767 (-32.768..32.767 1/s)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int16_t abx_wheelspeed_fl;
+
+ /**
+ * Range: -32768..32767 (-32.768..32.767 1/s)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int16_t abx_wheelspeed_fr;
+
+ /**
+ * Range: -32768..32767 (-32.768..32.767 1/s)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int16_t abx_wheelspeed_rl;
+
+ /**
+ * Range: -32768..32767 (-32.768..32.767 1/s)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int16_t abx_wheelspeed_rr;
+};
+
+/**
+ * Signals in message ABX_Dampers.
+ *
+ * Cycle time: 10ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_dampers_t {
+ /**
+ * Range: 0..7500 (0..75 mm)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_damper_heave_f;
+
+ /**
+ * Range: 0..7500 (0..75 mm)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_damper_roll_f;
+
+ /**
+ * Range: 0..7500 (0..75 mm)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_damper_heave_r;
+
+ /**
+ * Range: 0..7500 (0..75 mm)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_damper_roll_r;
+};
+
+/**
+ * Signals in message ABX_Timings.
+ *
+ * Cycle time: 1s
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_timings_t {
+ /**
+ * Range: 0..65535 (0..655.35 s)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_laptime_best;
+
+ /**
+ * Range: 0..65535 (0..655.35 s)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_laptime_last;
+
+ /**
+ * Range: 0..65535 (0..655.35 s)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_sectortime_best;
+
+ /**
+ * Range: 0..65535 (0..655.35 s)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint16_t abx_sectortime_last;
+};
+
+/**
+ * Signals in message ABX_Driver.
+ *
+ * Cycle time: 10ms
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_abx_driver_t {
+ /**
+ * Range: 0..100 (0..100 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t abx_apps_percent;
+
+ /**
+ * Range: 0..1600 (0..160 bar)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_brake_p_f;
+
+ /**
+ * Range: 0..1600 (0..160 bar)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t abx_brake_p_r;
+
+ /**
+ * Range: -128..127 (-128..127 �)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t abx_steering_angle;
+
+ /**
+ * Range: 0..255 (0..51 m/s)
+ * Scale: 0.2
+ * Offset: 0
+ */
+ uint8_t abx_speed;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t abx_lapcounter;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t abx_sectorcounter;
+};
+
+/**
+ * Signals in message TTS_Config.
+ *
+ * Sent only if TTS positions swapped
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_tts_config_t {
+ /**
+ * Range: 0..3 (0..3 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t tts_new_id;
+};
+
+/**
+ * Signals in message TTS_RR.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_tts_rr_t {
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rr_inner;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rr_center_in;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rr_center;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rr_center_out;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rr_outer;
+};
+
+/**
+ * Signals in message TTS_RL.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_tts_rl_t {
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rl_outer;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rl_center_out;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rl_center;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rl_center_in;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_rl_inner;
+};
+
+/**
+ * Signals in message TTS_FR.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_tts_fr_t {
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fr_inner;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fr_center_in;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fr_center;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fr_center_out;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fr_outer;
+};
+
+/**
+ * Signals in message TTS_FL.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_tts_fl_t {
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fl_outer;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fl_center_out;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fl_center;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fl_center_in;
+
+ /**
+ * Range: -2048..2047 (-54.8..354.7 �C)
+ * Scale: 0.1
+ * Offset: 150
+ */
+ int16_t tts_fl_inner;
+};
+
+/**
+ * Signals in message STW_Param_Set.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_stw_param_set_t {
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t stw_param_type;
+
+ /**
+ * Range: -
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint32_t stw_param_b_bal;
+
+ /**
+ * Range: 0..100 (0..1 -)
+ * Scale: 0.01
+ * Offset: 0
+ */
+ uint32_t stw_param_slipref;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t stw_param_asrp;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t stw_param_asron;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t stw_param_asri;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t stw_param_endu_power_limit;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t stw_param_test3;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t stw_param_test4;
+
+ /**
+ * Range: 0..10 (0..1 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint32_t stw_param_mumax;
+};
+
+/**
+ * Signals in message AMS_Slave0Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave0_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_error;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_id;
+
+ /**
+ * Range: 0..1 (0..1 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_status_so_c;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_min_cell_volt;
+
+ /**
+ * Range: 0..10000 (0..1 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t ams_slave_status_max_cell_volt;
+
+ /**
+ * Range: 0..16 (0..1 degC)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ int16_t ams_slave_status_max_temp;
+};
+
+/**
+ * Signals in message SSU_Message.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ssu_message_t {
+ /**
+ * Range: -1000..1000 (-1000..1000 Pa)
+ * Scale: 1
+ * Offset: 0
+ */
+ int16_t ssu_air_pressure;
+
+ /**
+ * Range: -200..800 (-20..80 �C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ int16_t ssu_air_temp;
+};
+
+/**
+ * Signals in message AMS_Status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_status_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_state;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_closed;
+
+ /**
+ * Range: 0..100 (0..100 %)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t soc;
+
+ /**
+ * Range: 0..50000 (0..5 V)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ uint16_t min_cell_volt;
+
+ /**
+ * Range: 0..65535 (0..4095.94 °C)
+ * Scale: 0.0625
+ * Offset: 0
+ */
+ uint16_t max_cell_temp;
+};
+
+/**
+ * Signals in message AMS_SlavePanic.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_slave_panic_t {
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_panic_slave_id;
+
+ /**
+ * Range: 0..72057600000000000 (0..7.20576e+16 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ams_slave_panic_kind;
+
+ /**
+ * Range: 0..72057600000000000 (0..7.20576e+16 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t ams_slave_panic_arg;
+};
+
+/**
+ * Signals in message AMS_In.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_ams_in_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ts_activate;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t inverters_discharged;
+
+ /**
+ * Range: 0..64 (0..64 Laps)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t lap_number;
+};
+
+/**
+ * Signals in message Shunt_Current.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_shunt_current_t {
+ /**
+ * Range: -2000000000..2000000000 (-2000000..2000000 A)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int32_t shunt_current;
+};
+
+/**
+ * Signals in message Shunt_Voltage1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_shunt_voltage1_t {
+ /**
+ * Range: -2000000000..2000000000 (-2000000..2000000 V)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int32_t shunt_voltage1;
+};
+
+/**
+ * Signals in message Shunt_Voltage2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_shunt_voltage2_t {
+ /**
+ * Range: -2000000000..2000000000 (-2000000..2000000 V)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int32_t shunt_voltage2;
+};
+
+/**
+ * Signals in message Shunt_Voltage3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_shunt_voltage3_t {
+ /**
+ * Range: -2000000000..2000000000 (-2000000..2000000 V)
+ * Scale: 0.001
+ * Offset: 0
+ */
+ int32_t shunt_voltage3;
+};
+
+/**
+ * Signals in message Shunt_Temperature.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_shunt_temperature_t {
+ /**
+ * Range: 0..10000 (0..1000 °C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint32_t shunt_temperature;
+};
+
+/**
+ * Signals in message SDCL_tx.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_sdcl_tx_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t asms_state;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_state_1;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_state_2;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_state_3;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t heartbeat_ok;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdcl_sdc_ready;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ts_start_muxed;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t latch_init_open;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t latch_closed;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t latch_reopened;
+
+ /**
+ * Range: 0..7 (0..7 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t as_mission;
+};
+
+/**
+ * Signals in message SDCL_rx.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_sdcl_rx_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t as_close_sdc;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdcl_heartbeat;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t asb_error;
+
+ /**
+ * Range: 0..7 (0..7 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t as_mission;
+};
+
+/**
+ * Signals in message PDU_Command.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_pdu_command_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_inverter_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_mode_valve_2_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_ebs_valve_2_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_shutdown_circuit_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_alwayson_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_misc_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_servo_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_led1_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_led2_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_led3_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_sensorbox_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_service_brake_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_ebs_valve_1_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_steering_rx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_mode_valve_1_rx;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_pwm_fans_rx;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_pwm_aggregat_rx;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_pwm_pump_rx;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_checksum_rx;
+};
+
+/**
+ * Signals in message PDU_Response.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_pdu_response_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_inverter_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_mode_valve_2_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_evs_valve_2_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_shutdown_circuit_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_alwayson_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_misc_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_servo_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_led1_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_led2_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_led3_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_sensorbox_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_service_brake_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_ebs_valve_1_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_steering_tx;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_mode_valve_1_tx;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_pwm_fans_tx;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_pwm_aggregat;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_pwm_pump;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdu_checksum_tx;
+};
+
+/**
+ * Signals in message TxPDO.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_tx_pdo_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_powersupply_less_8v;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_powersupply_greater_32v;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_canbus_timeout;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_canbus_startupmissing;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_canbus_statewarning;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_analoginput_middleposition;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_analoginput_cablebreak;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_analoginput_shortcircuit;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_analoginput_currentoverload;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_temperature_warning;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_temperature_shutdown;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_output1_controllerrange;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_output2_controllerrange;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_output1_cablebreak;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_output2_cablebreak;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_output1_shortcircuit;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t pdm_output2_shortcircuit;
+
+ /**
+ * Range: 0..65535 (0..65535 %.)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdm_analoginput;
+};
+
+/**
+ * Signals in message XSens_Error.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_error_t {
+ /**
+ * Dummy signal in empty message.
+ */
+ uint8_t dummy;
+};
+
+/**
+ * Signals in message XSens_Warning.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_warning_t {
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t warning_code;
+};
+
+/**
+ * Signals in message XSens_SampleTime.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_sample_time_t {
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint32_t timestamp;
+};
+
+/**
+ * Signals in message XSens_GroupCounter.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_group_counter_t {
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t counter;
+};
+
+/**
+ * Signals in message XSens_StatusWord.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_status_word_t {
+ /**
+ * Indicates that the 1PPS GNSS time pulse is present
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t have_gnss_time_pulse;
+
+ /**
+ * Mask for 2 bit RTK status field
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t rtk_status;
+
+ /**
+ * Mask for the 3 bit filter mode field
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t filter_mode;
+
+ /**
+ * Indicates if there was clipping on the Z-axis of the magnetometer
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_mag_z;
+
+ /**
+ * When set Indicates the sample was received as a retransmission
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t retransmitted;
+
+ /**
+ * When set Indicates clipping has occurred
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clipping_detected;
+
+ /**
+ * When set Indicates the sample is an interpolation between other samples
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t interpolated;
+
+ /**
+ * When set indicates a sync-in event has been triggered
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sync_in;
+
+ /**
+ * When set Indicates a sync-out event has been generated
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sync_out;
+
+ /**
+ * Indicates if there was clipping on the X-axis of the accelerometer
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_acc_x;
+
+ /**
+ * Indicates if there was clipping on the Y-axis of the accelerometer
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_acc_y;
+
+ /**
+ * Indicates if there was clipping on the Z-axis of the accelerometer
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_acc_z;
+
+ /**
+ * Indicates if there was clipping on the X-axis of the gyroscope
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_gyr_x;
+
+ /**
+ * Indicates if there was clipping on the Y-axis of the gyroscope
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_gyr_y;
+
+ /**
+ * Indicates if there was clipping on the Z-axis of the gyroscope
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_gyr_z;
+
+ /**
+ * Indicates if there was clipping on the X-axis of the magnetometer
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_mag_x;
+
+ /**
+ * Indicates if there was clipping on the Y-axis of the magnetometer
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t clip_mag_y;
+
+ /**
+ * Set when the self test result was ok
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t self_test_ok;
+
+ /**
+ * Set when the computed orientation is valid. The orientation may be invalid during startup or when the XSens data is clipping during violent (for the device) motion
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t orientation_valid;
+
+ /**
+ * Set when the device has a GPS receiver and the receiver says that there is a GPS position fix.
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t gps_valid;
+
+ /**
+ * Range: 0..3 (0..3 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t no_rotation;
+
+ /**
+ * Indicates if the In-Run Compass Calibration is doing the representative motion analysis
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t representative_motion;
+
+ /**
+ * Indicates whether the internal clock is synced with an external clock (Either GNNS or custom provided clock sync)
+ *
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t external_clock_synced;
+};
+
+/**
+ * Signals in message XSens_RateOfTurn.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_rate_of_turn_t {
+ /**
+ * Range: -17920..17920 (-35..35 rad/s)
+ * Scale: 0.00195313
+ * Offset: 0
+ */
+ int16_t x_sens_gyr_x;
+
+ /**
+ * Range: -17920..17920 (-35..35 rad/s)
+ * Scale: 0.00195313
+ * Offset: 0
+ */
+ int16_t x_sens_gyr_y;
+
+ /**
+ * Range: -17920..17920 (-35..35 rad/s)
+ * Scale: 0.00195313
+ * Offset: 0
+ */
+ int16_t x_sens_gyr_z;
+};
+
+/**
+ * Signals in message XSens_Acceleration.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_acceleration_t {
+ /**
+ * Range: -25600..25600 (-100..100 m/s²)
+ * Scale: 0.00390625
+ * Offset: 0
+ */
+ int16_t x_sens_acc_x;
+
+ /**
+ * Range: -25600..25600 (-100..100 m/s²)
+ * Scale: 0.00390625
+ * Offset: 0
+ */
+ int16_t x_sens_acc_y;
+
+ /**
+ * Range: -25600..25600 (-100..100 m/s²)
+ * Scale: 0.00390625
+ * Offset: 0
+ */
+ int16_t x_sens_acc_z;
+};
+
+/**
+ * Signals in message XSens_LongLat.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_long_lat_t {
+ /**
+ * Range: -1509950574..1509950574 (-90..90 deg)
+ * Scale: 5.96046e-08
+ * Offset: 0
+ */
+ int32_t latitude;
+
+ /**
+ * Range: -1509953108..1509953108 (-180..180 deg)
+ * Scale: 1.19209e-07
+ * Offset: 0
+ */
+ int32_t longitude;
+};
+
+/**
+ * Signals in message XSens_Velocity.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_x_sens_velocity_t {
+ /**
+ * Range: -32000..32000 (-500..500 m/s)
+ * Scale: 0.015625
+ * Offset: 0
+ */
+ int16_t vel_x;
+
+ /**
+ * Range: -32000..32000 (-500..500 m/s)
+ * Scale: 0.015625
+ * Offset: 0
+ */
+ int16_t vel_y;
+
+ /**
+ * Range: -32000..32000 (-500..500 m/s)
+ * Scale: 0.015625
+ * Offset: 0
+ */
+ int16_t vel_z;
+};
+
+/**
+ * Signals in message AS_Mission_fb.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_as_mission_fb_t {
+ /**
+ * Range: 1..7 (1..7 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t mission_selection;
+};
+
+/**
+ * Signals in message STW_mission_selected.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_stw_mission_selected_t {
+ /**
+ * Range: 1..7 (1..7 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t mission_selection;
+};
+
+/**
+ * Signals in message EPSC_out.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_epsc_out_t {
+ /**
+ * +-13875 equals to +-1.0, so the factor is 1/13875
+ *
+ * Range: -192515550..192515550 (-13875..13875 part of full steering)
+ * Scale: 7.20721e-05
+ * Offset: 0
+ */
+ int16_t epsc_measured_steering_angle;
+
+ /**
+ * Range: 0..255 (0..25.5 A)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_measured_current;
+
+ /**
+ * Range: 0..200 (0..20 V)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_measured_voltage;
+
+ /**
+ * Range: -2048..2047 (-204.8..204.7 rpm)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ int16_t epsc_measured_rpm;
+
+ /**
+ * Range: 0..1023 (0..102.3 °C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t epsc_measured_temperature;
+
+ /**
+ * Range: 0..1023 (0..102.3 °C)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint16_t epsc_measured_internal_temp;
+};
+
+/**
+ * Signals in message EPSC_Steering_In.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_epsc_steering_in_t {
+ /**
+ * Range: -100000000..100000000 (-10000..10000 -)
+ * Scale: 0.0001
+ * Offset: 0
+ */
+ int16_t epsc_desired_steering_angle;
+};
+
+/**
+ * Signals in message STW_buttons.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_stw_buttons_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t stw_button_left;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t stw_button_right;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t stw_button_r2_d;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t stw_button_enter;
+};
+
+/**
+ * Signals in message STW_status.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_stw_status_t {
+ /**
+ * Range: 0..5 (0..5 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t as_state_stw;
+
+ /**
+ * Range: 0..15 (0..15 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t r2_d_progress;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t inv_l_ready;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t inv_r_ready;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_bfl;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_brl;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_acc;
+
+ /**
+ * Range: -
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t sdc_hvb;
+
+ /**
+ * Range: 0..64 (0..64 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t lap_count;
+
+ /**
+ * Range: 0..255 (0..255 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t ini_chk_state;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_sdc;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_ams;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_pdu;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_ini_chk;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_con_mon;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_scs;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_s_bspd;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_app_sp;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_as;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_ros;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_res;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_inv_l;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t err_inv_r;
+};
+
+/**
+ * Signals in message PDU_Current_1.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_pdu_current_1_t {
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_alwayson_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_misc_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_inverter_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_shutdown_circuit_curr;
+};
+
+/**
+ * Signals in message PDU_Current_2.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_pdu_current_2_t {
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_fans_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_pump_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_aggregat_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_steering_curr;
+};
+
+/**
+ * Signals in message PDU_Current_3.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_pdu_current_3_t {
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_ebs_valve_1_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_ebs_valve_2_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_mode_valve_1_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_mode_valve_2_curr;
+};
+
+/**
+ * Signals in message PDU_Current_4.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_pdu_current_4_t {
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_sensorbox_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_service_brake_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_servos_curr;
+
+ /**
+ * Range: 0..65535 (0..65535 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint16_t pdu_shutdown_circuit_curr;
+};
+
+/**
+ * Signals in message EPSC_Config_In.
+ *
+ * All signal values are as on the CAN bus.
+ */
+struct can1__main_ft24_epsc_config_in_t {
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ int8_t epsc_should_calibrate;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_should_change_mode;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_mode;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_flag3;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_flag4;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_flag5;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_flag6;
+
+ /**
+ * Range: 0..1 (0..1 -)
+ * Scale: 1
+ * Offset: 0
+ */
+ uint8_t epsc_flag7;
+
+ /**
+ * Range: 0..256 (0..25.6 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_kp_pos;
+
+ /**
+ * Range: 0..256 (0..25.6 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_ki_pos;
+
+ /**
+ * Range: 0..256 (0..25.6 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_kp_rpm;
+
+ /**
+ * Range: 0..256 (0..25.6 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_ki_rpm;
+
+ /**
+ * Range: 0..256 (0..25.6 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_kp_curr;
+
+ /**
+ * Range: 0..256 (0..25.6 -)
+ * Scale: 0.1
+ * Offset: 0
+ */
+ uint8_t epsc_ki_curr;
+};
+
+/**
+ * Pack message ABX_ParamConfirm.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_param_confirm_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_param_confirm_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_ParamConfirm.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_param_confirm_unpack(
+ struct can1__main_ft24_abx_param_confirm_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_ParamConfirm.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_param_confirm_init(struct can1__main_ft24_abx_param_confirm_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_param_confirm_abx_param_confirm_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_param_confirm_abx_param_confirm_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_param_confirm_abx_param_confirm_is_in_range(uint8_t value);
+
+/**
+ * Pack message ABX_Hydraulics.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_hydraulics_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_hydraulics_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_Hydraulics.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_hydraulics_unpack(
+ struct can1__main_ft24_abx_hydraulics_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_Hydraulics.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_hydraulics_init(struct can1__main_ft24_abx_hydraulics_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_hydraulics_abx_hyd_pa_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_hydraulics_abx_hyd_pa_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_hydraulics_abx_hyd_pa_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_hydraulics_abx_hyd_pb_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_hydraulics_abx_hyd_pb_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_hydraulics_abx_hyd_pb_is_in_range(uint16_t value);
+
+/**
+ * Pack message JetsonTX.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_jetson_tx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_jetson_tx_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message JetsonTX.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_jetson_tx_unpack(
+ struct can1__main_ft24_jetson_tx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from JetsonTX.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_jetson_tx_init(struct can1__main_ft24_jetson_tx_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_as_mission_complete_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_as_mission_complete_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_as_mission_complete_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_as_ok_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_as_ok_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_as_ok_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_lap_count_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_lap_count_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_lap_count_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_speed_target_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_speed_target_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_speed_target_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_jetson_tx_jetson_steering_angle_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_steering_angle_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_steering_angle_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_brake_ratio_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_brake_ratio_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_brake_ratio_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_torque_ratio_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_torque_ratio_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_torque_ratio_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_cones_all_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_cones_all_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_cones_all_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_tx_jetson_cones_actual_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_tx_jetson_cones_actual_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_tx_jetson_cones_actual_is_in_range(uint8_t value);
+
+/**
+ * Pack message AMS_Slave0_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log0_unpack(
+ struct can1__main_ft24_ams_slave0_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log0_init(struct can1__main_ft24_ams_slave0_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave0_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log1_unpack(
+ struct can1__main_ft24_ams_slave0_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log1_init(struct can1__main_ft24_ams_slave0_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave0_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log2_unpack(
+ struct can1__main_ft24_ams_slave0_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log2_init(struct can1__main_ft24_ams_slave0_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave0_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log3_unpack(
+ struct can1__main_ft24_ams_slave0_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log3_init(struct can1__main_ft24_ams_slave0_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave0_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log4_unpack(
+ struct can1__main_ft24_ams_slave0_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log4_init(struct can1__main_ft24_ams_slave0_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_log4_ams_slave0_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log4_ams_slave0_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log4_ams_slave0_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave0_log4_ams_slave0_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log4_ams_slave0_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log4_ams_slave0_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave0_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log5_unpack(
+ struct can1__main_ft24_ams_slave0_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log5_init(struct can1__main_ft24_ams_slave0_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave0_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log6_unpack(
+ struct can1__main_ft24_ams_slave0_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log6_init(struct can1__main_ft24_ams_slave0_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave0_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log7_unpack(
+ struct can1__main_ft24_ams_slave0_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log7_init(struct can1__main_ft24_ams_slave0_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave0_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_log8_unpack(
+ struct can1__main_ft24_ams_slave0_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_log8_init(struct can1__main_ft24_ams_slave0_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave1_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log0_unpack(
+ struct can1__main_ft24_ams_slave1_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log0_init(struct can1__main_ft24_ams_slave1_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave1_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log1_unpack(
+ struct can1__main_ft24_ams_slave1_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log1_init(struct can1__main_ft24_ams_slave1_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave1_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log2_unpack(
+ struct can1__main_ft24_ams_slave1_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log2_init(struct can1__main_ft24_ams_slave1_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave1_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log3_unpack(
+ struct can1__main_ft24_ams_slave1_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log3_init(struct can1__main_ft24_ams_slave1_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave1_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log4_unpack(
+ struct can1__main_ft24_ams_slave1_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log4_init(struct can1__main_ft24_ams_slave1_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_log4_ams_slave1_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log4_ams_slave1_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log4_ams_slave1_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave1_log4_ams_slave1_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log4_ams_slave1_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log4_ams_slave1_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave1_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log5_unpack(
+ struct can1__main_ft24_ams_slave1_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log5_init(struct can1__main_ft24_ams_slave1_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave1_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log6_unpack(
+ struct can1__main_ft24_ams_slave1_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log6_init(struct can1__main_ft24_ams_slave1_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave1_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log7_unpack(
+ struct can1__main_ft24_ams_slave1_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log7_init(struct can1__main_ft24_ams_slave1_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave1_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_log8_unpack(
+ struct can1__main_ft24_ams_slave1_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_log8_init(struct can1__main_ft24_ams_slave1_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave2_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log0_unpack(
+ struct can1__main_ft24_ams_slave2_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log0_init(struct can1__main_ft24_ams_slave2_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave2_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log1_unpack(
+ struct can1__main_ft24_ams_slave2_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log1_init(struct can1__main_ft24_ams_slave2_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave2_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log2_unpack(
+ struct can1__main_ft24_ams_slave2_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log2_init(struct can1__main_ft24_ams_slave2_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave2_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log3_unpack(
+ struct can1__main_ft24_ams_slave2_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log3_init(struct can1__main_ft24_ams_slave2_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave2_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log4_unpack(
+ struct can1__main_ft24_ams_slave2_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log4_init(struct can1__main_ft24_ams_slave2_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_log4_ams_slave2_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log4_ams_slave2_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log4_ams_slave2_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave2_log4_ams_slave2_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log4_ams_slave2_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log4_ams_slave2_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave2_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log5_unpack(
+ struct can1__main_ft24_ams_slave2_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log5_init(struct can1__main_ft24_ams_slave2_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave2_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log6_unpack(
+ struct can1__main_ft24_ams_slave2_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log6_init(struct can1__main_ft24_ams_slave2_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave2_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log7_unpack(
+ struct can1__main_ft24_ams_slave2_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log7_init(struct can1__main_ft24_ams_slave2_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave2_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_log8_unpack(
+ struct can1__main_ft24_ams_slave2_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_log8_init(struct can1__main_ft24_ams_slave2_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave3_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log0_unpack(
+ struct can1__main_ft24_ams_slave3_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log0_init(struct can1__main_ft24_ams_slave3_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave3_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log1_unpack(
+ struct can1__main_ft24_ams_slave3_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log1_init(struct can1__main_ft24_ams_slave3_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave3_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log2_unpack(
+ struct can1__main_ft24_ams_slave3_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log2_init(struct can1__main_ft24_ams_slave3_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave3_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log3_unpack(
+ struct can1__main_ft24_ams_slave3_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log3_init(struct can1__main_ft24_ams_slave3_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave3_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log4_unpack(
+ struct can1__main_ft24_ams_slave3_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log4_init(struct can1__main_ft24_ams_slave3_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_log4_ams_slave3_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log4_ams_slave3_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log4_ams_slave3_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave3_log4_ams_slave3_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log4_ams_slave3_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log4_ams_slave3_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave3_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log5_unpack(
+ struct can1__main_ft24_ams_slave3_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log5_init(struct can1__main_ft24_ams_slave3_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave3_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log6_unpack(
+ struct can1__main_ft24_ams_slave3_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log6_init(struct can1__main_ft24_ams_slave3_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave3_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log7_unpack(
+ struct can1__main_ft24_ams_slave3_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log7_init(struct can1__main_ft24_ams_slave3_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave3_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_log8_unpack(
+ struct can1__main_ft24_ams_slave3_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_log8_init(struct can1__main_ft24_ams_slave3_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave4_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log0_unpack(
+ struct can1__main_ft24_ams_slave4_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log0_init(struct can1__main_ft24_ams_slave4_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave4_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log1_unpack(
+ struct can1__main_ft24_ams_slave4_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log1_init(struct can1__main_ft24_ams_slave4_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave4_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log2_unpack(
+ struct can1__main_ft24_ams_slave4_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log2_init(struct can1__main_ft24_ams_slave4_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave4_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log3_unpack(
+ struct can1__main_ft24_ams_slave4_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log3_init(struct can1__main_ft24_ams_slave4_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave4_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log4_unpack(
+ struct can1__main_ft24_ams_slave4_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log4_init(struct can1__main_ft24_ams_slave4_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_log4_ams_slave4_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log4_ams_slave4_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log4_ams_slave4_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave4_log4_ams_slave4_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log4_ams_slave4_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log4_ams_slave4_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave4_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log5_unpack(
+ struct can1__main_ft24_ams_slave4_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log5_init(struct can1__main_ft24_ams_slave4_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave4_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log6_unpack(
+ struct can1__main_ft24_ams_slave4_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log6_init(struct can1__main_ft24_ams_slave4_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave4_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log7_unpack(
+ struct can1__main_ft24_ams_slave4_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log7_init(struct can1__main_ft24_ams_slave4_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave4_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_log8_unpack(
+ struct can1__main_ft24_ams_slave4_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_log8_init(struct can1__main_ft24_ams_slave4_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave5_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log0_unpack(
+ struct can1__main_ft24_ams_slave5_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log0_init(struct can1__main_ft24_ams_slave5_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave5_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log1_unpack(
+ struct can1__main_ft24_ams_slave5_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log1_init(struct can1__main_ft24_ams_slave5_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave5_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log2_unpack(
+ struct can1__main_ft24_ams_slave5_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log2_init(struct can1__main_ft24_ams_slave5_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave5_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log3_unpack(
+ struct can1__main_ft24_ams_slave5_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log3_init(struct can1__main_ft24_ams_slave5_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave5_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log4_unpack(
+ struct can1__main_ft24_ams_slave5_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log4_init(struct can1__main_ft24_ams_slave5_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_log4_ams_slave5_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log4_ams_slave5_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log4_ams_slave5_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave5_log4_ams_slave5_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log4_ams_slave5_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log4_ams_slave5_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave5_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log5_unpack(
+ struct can1__main_ft24_ams_slave5_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log5_init(struct can1__main_ft24_ams_slave5_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave5_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log6_unpack(
+ struct can1__main_ft24_ams_slave5_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log6_init(struct can1__main_ft24_ams_slave5_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave5_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log7_unpack(
+ struct can1__main_ft24_ams_slave5_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log7_init(struct can1__main_ft24_ams_slave5_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave5_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_log8_unpack(
+ struct can1__main_ft24_ams_slave5_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_log8_init(struct can1__main_ft24_ams_slave5_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave6_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log0_unpack(
+ struct can1__main_ft24_ams_slave6_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log0_init(struct can1__main_ft24_ams_slave6_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave6_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log1_unpack(
+ struct can1__main_ft24_ams_slave6_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log1_init(struct can1__main_ft24_ams_slave6_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave6_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log2_unpack(
+ struct can1__main_ft24_ams_slave6_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log2_init(struct can1__main_ft24_ams_slave6_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave6_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log3_unpack(
+ struct can1__main_ft24_ams_slave6_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log3_init(struct can1__main_ft24_ams_slave6_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave6_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log4_unpack(
+ struct can1__main_ft24_ams_slave6_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log4_init(struct can1__main_ft24_ams_slave6_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_log4_ams_slave6_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log4_ams_slave6_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log4_ams_slave6_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave6_log4_ams_slave6_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log4_ams_slave6_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log4_ams_slave6_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave6_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log5_unpack(
+ struct can1__main_ft24_ams_slave6_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log5_init(struct can1__main_ft24_ams_slave6_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave6_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log6_unpack(
+ struct can1__main_ft24_ams_slave6_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log6_init(struct can1__main_ft24_ams_slave6_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave6_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log7_unpack(
+ struct can1__main_ft24_ams_slave6_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log7_init(struct can1__main_ft24_ams_slave6_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave6_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_log8_unpack(
+ struct can1__main_ft24_ams_slave6_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_log8_init(struct can1__main_ft24_ams_slave6_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave7_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log0_unpack(
+ struct can1__main_ft24_ams_slave7_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log0_init(struct can1__main_ft24_ams_slave7_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave7_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log1_unpack(
+ struct can1__main_ft24_ams_slave7_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log1_init(struct can1__main_ft24_ams_slave7_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave7_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log2_unpack(
+ struct can1__main_ft24_ams_slave7_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log2_init(struct can1__main_ft24_ams_slave7_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave7_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log3_unpack(
+ struct can1__main_ft24_ams_slave7_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log3_init(struct can1__main_ft24_ams_slave7_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave7_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log4_unpack(
+ struct can1__main_ft24_ams_slave7_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log4_init(struct can1__main_ft24_ams_slave7_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_log4_ams_slave7_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log4_ams_slave7_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log4_ams_slave7_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave7_log4_ams_slave7_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log4_ams_slave7_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log4_ams_slave7_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave7_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log5_unpack(
+ struct can1__main_ft24_ams_slave7_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log5_init(struct can1__main_ft24_ams_slave7_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave7_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log6_unpack(
+ struct can1__main_ft24_ams_slave7_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log6_init(struct can1__main_ft24_ams_slave7_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave7_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log7_unpack(
+ struct can1__main_ft24_ams_slave7_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log7_init(struct can1__main_ft24_ams_slave7_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave7_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_log8_unpack(
+ struct can1__main_ft24_ams_slave7_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_log8_init(struct can1__main_ft24_ams_slave7_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave8_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log0_unpack(
+ struct can1__main_ft24_ams_slave8_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log0_init(struct can1__main_ft24_ams_slave8_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave8_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log1_unpack(
+ struct can1__main_ft24_ams_slave8_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log1_init(struct can1__main_ft24_ams_slave8_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave8_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log2_unpack(
+ struct can1__main_ft24_ams_slave8_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log2_init(struct can1__main_ft24_ams_slave8_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave8_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log3_unpack(
+ struct can1__main_ft24_ams_slave8_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log3_init(struct can1__main_ft24_ams_slave8_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave8_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log4_unpack(
+ struct can1__main_ft24_ams_slave8_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log4_init(struct can1__main_ft24_ams_slave8_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_log4_ams_slave8_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log4_ams_slave8_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log4_ams_slave8_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave8_log4_ams_slave8_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log4_ams_slave8_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log4_ams_slave8_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave8_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log5_unpack(
+ struct can1__main_ft24_ams_slave8_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log5_init(struct can1__main_ft24_ams_slave8_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave8_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log6_unpack(
+ struct can1__main_ft24_ams_slave8_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log6_init(struct can1__main_ft24_ams_slave8_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave8_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log7_unpack(
+ struct can1__main_ft24_ams_slave8_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log7_init(struct can1__main_ft24_ams_slave8_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave8_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_log8_unpack(
+ struct can1__main_ft24_ams_slave8_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_log8_init(struct can1__main_ft24_ams_slave8_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave9_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log0_unpack(
+ struct can1__main_ft24_ams_slave9_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log0_init(struct can1__main_ft24_ams_slave9_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave9_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log1_unpack(
+ struct can1__main_ft24_ams_slave9_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log1_init(struct can1__main_ft24_ams_slave9_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave9_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log2_unpack(
+ struct can1__main_ft24_ams_slave9_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log2_init(struct can1__main_ft24_ams_slave9_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave9_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log3_unpack(
+ struct can1__main_ft24_ams_slave9_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log3_init(struct can1__main_ft24_ams_slave9_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave9_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log4_unpack(
+ struct can1__main_ft24_ams_slave9_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log4_init(struct can1__main_ft24_ams_slave9_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_log4_ams_slave9_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log4_ams_slave9_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log4_ams_slave9_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave9_log4_ams_slave9_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log4_ams_slave9_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log4_ams_slave9_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave9_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log5_unpack(
+ struct can1__main_ft24_ams_slave9_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log5_init(struct can1__main_ft24_ams_slave9_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave9_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log6_unpack(
+ struct can1__main_ft24_ams_slave9_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log6_init(struct can1__main_ft24_ams_slave9_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave9_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log7_unpack(
+ struct can1__main_ft24_ams_slave9_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log7_init(struct can1__main_ft24_ams_slave9_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave9_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_log8_unpack(
+ struct can1__main_ft24_ams_slave9_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_log8_init(struct can1__main_ft24_ams_slave9_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave10_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log0_unpack(
+ struct can1__main_ft24_ams_slave10_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log0_init(struct can1__main_ft24_ams_slave10_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave10_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log1_unpack(
+ struct can1__main_ft24_ams_slave10_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log1_init(struct can1__main_ft24_ams_slave10_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave10_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log2_unpack(
+ struct can1__main_ft24_ams_slave10_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log2_init(struct can1__main_ft24_ams_slave10_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave10_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log3_unpack(
+ struct can1__main_ft24_ams_slave10_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log3_init(struct can1__main_ft24_ams_slave10_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave10_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log4_unpack(
+ struct can1__main_ft24_ams_slave10_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log4_init(struct can1__main_ft24_ams_slave10_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_log4_ams_slave10_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log4_ams_slave10_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log4_ams_slave10_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave10_log4_ams_slave10_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log4_ams_slave10_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log4_ams_slave10_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave10_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log5_unpack(
+ struct can1__main_ft24_ams_slave10_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log5_init(struct can1__main_ft24_ams_slave10_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave10_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log6_unpack(
+ struct can1__main_ft24_ams_slave10_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log6_init(struct can1__main_ft24_ams_slave10_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave10_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log7_unpack(
+ struct can1__main_ft24_ams_slave10_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log7_init(struct can1__main_ft24_ams_slave10_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave10_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_log8_unpack(
+ struct can1__main_ft24_ams_slave10_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_log8_init(struct can1__main_ft24_ams_slave10_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave11_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log0_unpack(
+ struct can1__main_ft24_ams_slave11_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log0_init(struct can1__main_ft24_ams_slave11_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave11_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log1_unpack(
+ struct can1__main_ft24_ams_slave11_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log1_init(struct can1__main_ft24_ams_slave11_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave11_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log2_unpack(
+ struct can1__main_ft24_ams_slave11_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log2_init(struct can1__main_ft24_ams_slave11_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave11_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log3_unpack(
+ struct can1__main_ft24_ams_slave11_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log3_init(struct can1__main_ft24_ams_slave11_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave11_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log4_unpack(
+ struct can1__main_ft24_ams_slave11_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log4_init(struct can1__main_ft24_ams_slave11_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_log4_ams_slave11_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log4_ams_slave11_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log4_ams_slave11_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave11_log4_ams_slave11_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log4_ams_slave11_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log4_ams_slave11_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave11_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log5_unpack(
+ struct can1__main_ft24_ams_slave11_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log5_init(struct can1__main_ft24_ams_slave11_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave11_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log6_unpack(
+ struct can1__main_ft24_ams_slave11_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log6_init(struct can1__main_ft24_ams_slave11_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave11_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log7_unpack(
+ struct can1__main_ft24_ams_slave11_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log7_init(struct can1__main_ft24_ams_slave11_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave11_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_log8_unpack(
+ struct can1__main_ft24_ams_slave11_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_log8_init(struct can1__main_ft24_ams_slave11_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave12_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log0_unpack(
+ struct can1__main_ft24_ams_slave12_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log0_init(struct can1__main_ft24_ams_slave12_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave12_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log1_unpack(
+ struct can1__main_ft24_ams_slave12_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log1_init(struct can1__main_ft24_ams_slave12_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave12_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log2_unpack(
+ struct can1__main_ft24_ams_slave12_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log2_init(struct can1__main_ft24_ams_slave12_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave12_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log3_unpack(
+ struct can1__main_ft24_ams_slave12_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log3_init(struct can1__main_ft24_ams_slave12_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave12_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log4_unpack(
+ struct can1__main_ft24_ams_slave12_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log4_init(struct can1__main_ft24_ams_slave12_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_log4_ams_slave12_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log4_ams_slave12_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log4_ams_slave12_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave12_log4_ams_slave12_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log4_ams_slave12_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log4_ams_slave12_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave12_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log5_unpack(
+ struct can1__main_ft24_ams_slave12_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log5_init(struct can1__main_ft24_ams_slave12_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave12_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log6_unpack(
+ struct can1__main_ft24_ams_slave12_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log6_init(struct can1__main_ft24_ams_slave12_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave12_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log7_unpack(
+ struct can1__main_ft24_ams_slave12_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log7_init(struct can1__main_ft24_ams_slave12_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave12_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_log8_unpack(
+ struct can1__main_ft24_ams_slave12_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_log8_init(struct can1__main_ft24_ams_slave12_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave13_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log0_unpack(
+ struct can1__main_ft24_ams_slave13_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log0_init(struct can1__main_ft24_ams_slave13_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave13_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log1_unpack(
+ struct can1__main_ft24_ams_slave13_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log1_init(struct can1__main_ft24_ams_slave13_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave13_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log2_unpack(
+ struct can1__main_ft24_ams_slave13_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log2_init(struct can1__main_ft24_ams_slave13_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave13_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log3_unpack(
+ struct can1__main_ft24_ams_slave13_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log3_init(struct can1__main_ft24_ams_slave13_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave13_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log4_unpack(
+ struct can1__main_ft24_ams_slave13_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log4_init(struct can1__main_ft24_ams_slave13_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_log4_ams_slave13_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log4_ams_slave13_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log4_ams_slave13_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave13_log4_ams_slave13_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log4_ams_slave13_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log4_ams_slave13_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave13_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log5_unpack(
+ struct can1__main_ft24_ams_slave13_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log5_init(struct can1__main_ft24_ams_slave13_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave13_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log6_unpack(
+ struct can1__main_ft24_ams_slave13_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log6_init(struct can1__main_ft24_ams_slave13_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave13_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log7_unpack(
+ struct can1__main_ft24_ams_slave13_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log7_init(struct can1__main_ft24_ams_slave13_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave13_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_log8_unpack(
+ struct can1__main_ft24_ams_slave13_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_log8_init(struct can1__main_ft24_ams_slave13_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave14_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log0_unpack(
+ struct can1__main_ft24_ams_slave14_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log0_init(struct can1__main_ft24_ams_slave14_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave14_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log1_unpack(
+ struct can1__main_ft24_ams_slave14_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log1_init(struct can1__main_ft24_ams_slave14_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave14_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log2_unpack(
+ struct can1__main_ft24_ams_slave14_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log2_init(struct can1__main_ft24_ams_slave14_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave14_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log3_unpack(
+ struct can1__main_ft24_ams_slave14_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log3_init(struct can1__main_ft24_ams_slave14_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave14_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log4_unpack(
+ struct can1__main_ft24_ams_slave14_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log4_init(struct can1__main_ft24_ams_slave14_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_log4_ams_slave14_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log4_ams_slave14_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log4_ams_slave14_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave14_log4_ams_slave14_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log4_ams_slave14_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log4_ams_slave14_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave14_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log5_unpack(
+ struct can1__main_ft24_ams_slave14_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log5_init(struct can1__main_ft24_ams_slave14_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave14_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log6_unpack(
+ struct can1__main_ft24_ams_slave14_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log6_init(struct can1__main_ft24_ams_slave14_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave14_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log7_unpack(
+ struct can1__main_ft24_ams_slave14_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log7_init(struct can1__main_ft24_ams_slave14_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave14_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_log8_unpack(
+ struct can1__main_ft24_ams_slave14_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_log8_init(struct can1__main_ft24_ams_slave14_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave15_Log0.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log0_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log0.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log0_unpack(
+ struct can1__main_ft24_ams_slave15_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log0.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log0_init(struct can1__main_ft24_ams_slave15_log0_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v0_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v0_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v1_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v1_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v2_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v2_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v3_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v3_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave15_Log1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log1_unpack(
+ struct can1__main_ft24_ams_slave15_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log1_init(struct can1__main_ft24_ams_slave15_log1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v4_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v4_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v5_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v5_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v6_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v6_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v7_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v7_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave15_Log2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log2_unpack(
+ struct can1__main_ft24_ams_slave15_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log2_init(struct can1__main_ft24_ams_slave15_log2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v8_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v8_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v9_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v9_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v10_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v10_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v11_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v11_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave15_Log3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log3_unpack(
+ struct can1__main_ft24_ams_slave15_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log3_init(struct can1__main_ft24_ams_slave15_log3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v12_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v12_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v13_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v13_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v14_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v14_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v15_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v15_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_Slave15_Log4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log4_unpack(
+ struct can1__main_ft24_ams_slave15_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log4_init(struct can1__main_ft24_ams_slave15_log4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_log4_ams_slave15_v16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log4_ams_slave15_v16_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log4_ams_slave15_v16_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave15_log4_ams_slave15_failed_sensors_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log4_ams_slave15_failed_sensors_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log4_ams_slave15_failed_sensors_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave15_Log5.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log5_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log5.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log5_unpack(
+ struct can1__main_ft24_ams_slave15_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log5.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log5_init(struct can1__main_ft24_ams_slave15_log5_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t0_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t0_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t0_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t1_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t1_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t2_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t2_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t3_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t3_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t4_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t4_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t5_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t5_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t6_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t6_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t7_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t7_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave15_Log6.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log6_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log6.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log6_unpack(
+ struct can1__main_ft24_ams_slave15_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log6.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log6_init(struct can1__main_ft24_ams_slave15_log6_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t8_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t8_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t8_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t9_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t9_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t9_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t10_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t10_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t10_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t11_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t11_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t11_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t12_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t12_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t12_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t13_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t13_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t13_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t14_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t14_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t14_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t15_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t15_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t15_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave15_Log7.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log7_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log7.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log7_unpack(
+ struct can1__main_ft24_ams_slave15_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log7.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log7_init(struct can1__main_ft24_ams_slave15_log7_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t16_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t16_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t16_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t17_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t17_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t17_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t18_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t18_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t18_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t19_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t19_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t19_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t20_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t20_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t20_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t21_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t21_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t21_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t22_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t22_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t22_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t23_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t23_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t23_is_in_range(int8_t value);
+
+/**
+ * Pack message AMS_Slave15_Log8.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log8_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15_Log8.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_log8_unpack(
+ struct can1__main_ft24_ams_slave15_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15_Log8.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_log8_init(struct can1__main_ft24_ams_slave15_log8_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t24_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t24_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t24_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t25_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t25_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t25_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t26_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t26_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t26_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t27_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t27_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t27_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t28_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t28_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t28_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t29_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t29_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t29_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t30_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t30_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t30_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t31_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t31_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t31_is_in_range(int8_t value);
+
+/**
+ * Pack message JetsonRX.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_jetson_rx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_jetson_rx_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message JetsonRX.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_jetson_rx_unpack(
+ struct can1__main_ft24_jetson_rx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from JetsonRX.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_jetson_rx_init(struct can1__main_ft24_jetson_rx_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_as_mission_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_as_mission_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_as_mission_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_as_state_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_as_state_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_as_state_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_power_off_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_power_off_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_power_off_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_reset_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_reset_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_reset_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_speed_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_speed_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_speed_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_speed_x_sens_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_speed_x_sens_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_speed_x_sens_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_jetson_rx_jetson_allow_torque_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_jetson_rx_jetson_allow_torque_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_jetson_rx_jetson_allow_torque_is_in_range(uint8_t value);
+
+/**
+ * Pack message AMS_Slave15Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave15_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave15Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave15_status_unpack(
+ struct can1__main_ft24_ams_slave15_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave15Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave15_status_init(struct can1__main_ft24_ams_slave15_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave15_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave15_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave15_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave15_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave15_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave15_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave14Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave14_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave14Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave14_status_unpack(
+ struct can1__main_ft24_ams_slave14_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave14Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave14_status_init(struct can1__main_ft24_ams_slave14_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave14_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave14_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave14_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave14_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave14_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave14_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave13Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave13_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave13Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave13_status_unpack(
+ struct can1__main_ft24_ams_slave13_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave13Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave13_status_init(struct can1__main_ft24_ams_slave13_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave13_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave13_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave13_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave13_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave13_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave13_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave12Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave12_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave12Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave12_status_unpack(
+ struct can1__main_ft24_ams_slave12_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave12Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave12_status_init(struct can1__main_ft24_ams_slave12_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave12_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave12_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave12_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave12_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave12_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave12_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave11Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave11_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave11Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave11_status_unpack(
+ struct can1__main_ft24_ams_slave11_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave11Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave11_status_init(struct can1__main_ft24_ams_slave11_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave11_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave11_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave11_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave11_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave11_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave11_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave10Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave10_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave10Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave10_status_unpack(
+ struct can1__main_ft24_ams_slave10_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave10Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave10_status_init(struct can1__main_ft24_ams_slave10_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave10_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave10_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave10_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave10_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave10_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave10_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave9Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave9_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave9Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave9_status_unpack(
+ struct can1__main_ft24_ams_slave9_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave9Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave9_status_init(struct can1__main_ft24_ams_slave9_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave9_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave9_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave9_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave9_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave9_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave9_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave8Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave8_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave8Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave8_status_unpack(
+ struct can1__main_ft24_ams_slave8_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave8Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave8_status_init(struct can1__main_ft24_ams_slave8_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave8_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave8_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave8_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave8_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave8_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave8_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave7Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave7_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave7Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave7_status_unpack(
+ struct can1__main_ft24_ams_slave7_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave7Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave7_status_init(struct can1__main_ft24_ams_slave7_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave7_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave7_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave7_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave7_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave7_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave7_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave6Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave6_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave6Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave6_status_unpack(
+ struct can1__main_ft24_ams_slave6_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave6Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave6_status_init(struct can1__main_ft24_ams_slave6_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave6_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave6_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave6_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave6_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave6_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave6_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave5Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave5_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave5Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave5_status_unpack(
+ struct can1__main_ft24_ams_slave5_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave5Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave5_status_init(struct can1__main_ft24_ams_slave5_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave5_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave5_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave5_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave5_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave5_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave5_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave4Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave4_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave4Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave4_status_unpack(
+ struct can1__main_ft24_ams_slave4_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave4Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave4_status_init(struct can1__main_ft24_ams_slave4_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave4_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave4_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave4_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave4_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave4_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave4_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave3Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave3_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave3Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave3_status_unpack(
+ struct can1__main_ft24_ams_slave3_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave3Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave3_status_init(struct can1__main_ft24_ams_slave3_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave3_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave3_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave3_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave3_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave3_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave3_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave2Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave2_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave2Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave2_status_unpack(
+ struct can1__main_ft24_ams_slave2_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave2Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave2_status_init(struct can1__main_ft24_ams_slave2_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave2_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave2_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave2_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave2_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave2_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave2_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Slave1Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave1_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave1Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave1_status_unpack(
+ struct can1__main_ft24_ams_slave1_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave1Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave1_status_init(struct can1__main_ft24_ams_slave1_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave1_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave1_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave1_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave1_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave1_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave1_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message ABX_Misc.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_misc_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_misc_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_Misc.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_misc_unpack(
+ struct can1__main_ft24_abx_misc_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_Misc.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_misc_init(struct can1__main_ft24_abx_misc_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_misc_abx_driver_protocol_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_misc_abx_driver_protocol_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_misc_abx_driver_protocol_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_misc_abx_distance_session_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_misc_abx_distance_session_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_misc_abx_distance_session_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_misc_abx_distance_total_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_misc_abx_distance_total_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_misc_abx_distance_total_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_misc_abx_lv_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_misc_abx_lv_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_misc_abx_lv_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_misc_abx_lv_voltage_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_misc_abx_lv_voltage_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_misc_abx_lv_voltage_is_in_range(uint8_t value);
+
+/**
+ * Pack message AMS_Error.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_error_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_error_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Error.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_error_unpack(
+ struct can1__main_ft24_ams_error_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Error.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_error_init(struct can1__main_ft24_ams_error_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_error_ams_error_kind_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_error_ams_error_kind_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_error_ams_error_kind_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_ams_error_ams_error_arg_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_error_ams_error_arg_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_error_ams_error_arg_is_in_range(int8_t value);
+
+/**
+ * Pack message ABX_CoolingSys_Internal.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_cooling_sys_internal_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_cooling_sys_internal_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_CoolingSys_Internal.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_cooling_sys_internal_unpack(
+ struct can1__main_ft24_abx_cooling_sys_internal_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_CoolingSys_Internal.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_cooling_sys_internal_init(struct can1__main_ft24_abx_cooling_sys_internal_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_l_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_l_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_l_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_r_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_r_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_r_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_l_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_l_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_l_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_r_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_r_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_r_is_in_range(uint16_t value);
+
+/**
+ * Pack message ABX_CoolingSys_Acc.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_cooling_sys_acc_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_cooling_sys_acc_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_CoolingSys_Acc.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_cooling_sys_acc_unpack(
+ struct can1__main_ft24_abx_cooling_sys_acc_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_CoolingSys_Acc.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_cooling_sys_acc_init(struct can1__main_ft24_abx_cooling_sys_acc_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_in_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_in_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_out_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_out_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_in_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_in_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_out_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_out_is_in_range(uint16_t value);
+
+/**
+ * Pack message ABX_CoolingSys_MotInv.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_cooling_sys_mot_inv_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_cooling_sys_mot_inv_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_CoolingSys_MotInv.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_cooling_sys_mot_inv_unpack(
+ struct can1__main_ft24_abx_cooling_sys_mot_inv_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_CoolingSys_MotInv.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_cooling_sys_mot_inv_init(struct can1__main_ft24_abx_cooling_sys_mot_inv_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_inv_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_inv_in_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_inv_in_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_l_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_l_in_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_l_in_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_rad_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_rad_in_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_rad_in_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_r_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_r_in_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_r_in_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_inv_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_inv_in_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_inv_in_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_mot_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_mot_in_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_mot_in_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_rad_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_rad_in_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_rad_in_is_in_range(uint16_t value);
+
+/**
+ * Pack message ABX_BrakeT.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_brake_t_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_brake_t_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_BrakeT.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_brake_t_unpack(
+ struct can1__main_ft24_abx_brake_t_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_BrakeT.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_brake_t_init(struct can1__main_ft24_abx_brake_t_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_fl_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_brake_t_abx_brake_t_fl_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_brake_t_abx_brake_t_fl_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_fr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_brake_t_abx_brake_t_fr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_brake_t_abx_brake_t_fr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_rl_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_brake_t_abx_brake_t_rl_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_brake_t_abx_brake_t_rl_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_rr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_brake_t_abx_brake_t_rr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_brake_t_abx_brake_t_rr_is_in_range(uint16_t value);
+
+/**
+ * Pack message ABX_Wheelspeed.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_wheelspeed_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_wheelspeed_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_Wheelspeed.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_wheelspeed_unpack(
+ struct can1__main_ft24_abx_wheelspeed_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_Wheelspeed.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_wheelspeed_init(struct can1__main_ft24_abx_wheelspeed_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fl_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fl_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fl_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fr_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fr_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rl_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rl_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rl_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rr_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rr_is_in_range(int16_t value);
+
+/**
+ * Pack message ABX_Dampers.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_dampers_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_dampers_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_Dampers.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_dampers_unpack(
+ struct can1__main_ft24_abx_dampers_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_Dampers.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_dampers_init(struct can1__main_ft24_abx_dampers_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_dampers_abx_damper_heave_f_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_dampers_abx_damper_heave_f_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_dampers_abx_damper_heave_f_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_dampers_abx_damper_roll_f_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_dampers_abx_damper_roll_f_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_dampers_abx_damper_roll_f_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_dampers_abx_damper_heave_r_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_dampers_abx_damper_heave_r_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_dampers_abx_damper_heave_r_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_dampers_abx_damper_roll_r_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_dampers_abx_damper_roll_r_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_dampers_abx_damper_roll_r_is_in_range(uint16_t value);
+
+/**
+ * Pack message ABX_Timings.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_timings_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_timings_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_Timings.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_timings_unpack(
+ struct can1__main_ft24_abx_timings_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_Timings.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_timings_init(struct can1__main_ft24_abx_timings_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_timings_abx_laptime_best_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_timings_abx_laptime_best_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_timings_abx_laptime_best_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_timings_abx_laptime_last_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_timings_abx_laptime_last_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_timings_abx_laptime_last_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_timings_abx_sectortime_best_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_timings_abx_sectortime_best_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_timings_abx_sectortime_best_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_timings_abx_sectortime_last_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_timings_abx_sectortime_last_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_timings_abx_sectortime_last_is_in_range(uint16_t value);
+
+/**
+ * Pack message ABX_Driver.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_abx_driver_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_driver_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message ABX_Driver.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_abx_driver_unpack(
+ struct can1__main_ft24_abx_driver_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from ABX_Driver.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_abx_driver_init(struct can1__main_ft24_abx_driver_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_driver_abx_apps_percent_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_apps_percent_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_apps_percent_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_driver_abx_brake_p_f_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_brake_p_f_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_brake_p_f_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_abx_driver_abx_brake_p_r_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_brake_p_r_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_brake_p_r_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_abx_driver_abx_steering_angle_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_steering_angle_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_steering_angle_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_driver_abx_speed_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_speed_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_speed_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_driver_abx_lapcounter_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_lapcounter_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_lapcounter_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_abx_driver_abx_sectorcounter_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_abx_driver_abx_sectorcounter_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_abx_driver_abx_sectorcounter_is_in_range(uint8_t value);
+
+/**
+ * Pack message TTS_Config.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_tts_config_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_config_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message TTS_Config.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_tts_config_unpack(
+ struct can1__main_ft24_tts_config_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from TTS_Config.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_tts_config_init(struct can1__main_ft24_tts_config_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tts_config_tts_new_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_config_tts_new_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_config_tts_new_id_is_in_range(uint8_t value);
+
+/**
+ * Pack message TTS_RR.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_tts_rr_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_rr_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message TTS_RR.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_tts_rr_unpack(
+ struct can1__main_ft24_tts_rr_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from TTS_RR.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_tts_rr_init(struct can1__main_ft24_tts_rr_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rr_tts_rr_inner_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rr_tts_rr_inner_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rr_tts_rr_inner_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rr_tts_rr_center_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rr_tts_rr_center_in_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rr_tts_rr_center_in_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rr_tts_rr_center_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rr_tts_rr_center_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rr_tts_rr_center_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rr_tts_rr_center_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rr_tts_rr_center_out_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rr_tts_rr_center_out_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rr_tts_rr_outer_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rr_tts_rr_outer_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rr_tts_rr_outer_is_in_range(int16_t value);
+
+/**
+ * Pack message TTS_RL.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_tts_rl_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_rl_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message TTS_RL.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_tts_rl_unpack(
+ struct can1__main_ft24_tts_rl_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from TTS_RL.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_tts_rl_init(struct can1__main_ft24_tts_rl_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rl_tts_rl_outer_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rl_tts_rl_outer_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rl_tts_rl_outer_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rl_tts_rl_center_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rl_tts_rl_center_out_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rl_tts_rl_center_out_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rl_tts_rl_center_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rl_tts_rl_center_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rl_tts_rl_center_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rl_tts_rl_center_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rl_tts_rl_center_in_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rl_tts_rl_center_in_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_rl_tts_rl_inner_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_rl_tts_rl_inner_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_rl_tts_rl_inner_is_in_range(int16_t value);
+
+/**
+ * Pack message TTS_FR.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_tts_fr_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_fr_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message TTS_FR.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_tts_fr_unpack(
+ struct can1__main_ft24_tts_fr_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from TTS_FR.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_tts_fr_init(struct can1__main_ft24_tts_fr_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fr_tts_fr_inner_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fr_tts_fr_inner_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fr_tts_fr_inner_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fr_tts_fr_center_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fr_tts_fr_center_in_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fr_tts_fr_center_in_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fr_tts_fr_center_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fr_tts_fr_center_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fr_tts_fr_center_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fr_tts_fr_center_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fr_tts_fr_center_out_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fr_tts_fr_center_out_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fr_tts_fr_outer_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fr_tts_fr_outer_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fr_tts_fr_outer_is_in_range(int16_t value);
+
+/**
+ * Pack message TTS_FL.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_tts_fl_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_fl_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message TTS_FL.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_tts_fl_unpack(
+ struct can1__main_ft24_tts_fl_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from TTS_FL.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_tts_fl_init(struct can1__main_ft24_tts_fl_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fl_tts_fl_outer_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fl_tts_fl_outer_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fl_tts_fl_outer_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fl_tts_fl_center_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fl_tts_fl_center_out_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fl_tts_fl_center_out_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fl_tts_fl_center_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fl_tts_fl_center_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fl_tts_fl_center_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fl_tts_fl_center_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fl_tts_fl_center_in_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fl_tts_fl_center_in_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_tts_fl_tts_fl_inner_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tts_fl_tts_fl_inner_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tts_fl_tts_fl_inner_is_in_range(int16_t value);
+
+/**
+ * Pack message STW_Param_Set.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_stw_param_set_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_param_set_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message STW_Param_Set.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_stw_param_set_unpack(
+ struct can1__main_ft24_stw_param_set_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from STW_Param_Set.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_stw_param_set_init(struct can1__main_ft24_stw_param_set_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_param_set_stw_param_type_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_type_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_type_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_b_bal_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_b_bal_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_b_bal_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_slipref_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_slipref_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_slipref_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_asrp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_asrp_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_asrp_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_asron_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_asron_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_asron_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_asri_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_asri_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_asri_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_endu_power_limit_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_endu_power_limit_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_endu_power_limit_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_test3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_test3_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_test3_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_test4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_test4_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_test4_is_in_range(uint32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_stw_param_set_stw_param_mumax_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_param_set_stw_param_mumax_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_param_set_stw_param_mumax_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_Slave0Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave0_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Slave0Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave0_status_unpack(
+ struct can1__main_ft24_ams_slave0_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Slave0Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave0_status_init(struct can1__main_ft24_ams_slave0_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave0_status_ams_slave_status_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_status_ams_slave_status_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave0_status_ams_slave_status_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_status_ams_slave_status_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave0_status_ams_slave_status_so_c_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_status_ams_slave_status_so_c_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_so_c_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_status_ams_slave_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_status_ams_slave_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_slave0_status_ams_slave_status_max_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_status_ams_slave_status_max_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ams_slave0_status_ams_slave_status_max_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave0_status_ams_slave_status_max_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_max_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message SSU_Message.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ssu_message_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ssu_message_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message SSU_Message.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ssu_message_unpack(
+ struct can1__main_ft24_ssu_message_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from SSU_Message.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ssu_message_init(struct can1__main_ft24_ssu_message_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ssu_message_ssu_air_pressure_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ssu_message_ssu_air_pressure_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ssu_message_ssu_air_pressure_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_ssu_message_ssu_air_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ssu_message_ssu_air_temp_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ssu_message_ssu_air_temp_is_in_range(int16_t value);
+
+/**
+ * Pack message AMS_Status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_Status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_status_unpack(
+ struct can1__main_ft24_ams_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_Status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_status_init(struct can1__main_ft24_ams_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_status_ams_state_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_status_ams_state_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_status_ams_state_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_status_sdc_closed_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_status_sdc_closed_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_status_sdc_closed_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_status_soc_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_status_soc_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_status_soc_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_status_min_cell_volt_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_status_min_cell_volt_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_status_min_cell_volt_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_ams_status_max_cell_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_status_max_cell_temp_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_status_max_cell_temp_is_in_range(uint16_t value);
+
+/**
+ * Pack message AMS_SlavePanic.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_slave_panic_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave_panic_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_SlavePanic.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_slave_panic_unpack(
+ struct can1__main_ft24_ams_slave_panic_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_SlavePanic.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_slave_panic_init(struct can1__main_ft24_ams_slave_panic_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave_panic_ams_slave_panic_slave_id_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave_panic_ams_slave_panic_slave_id_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave_panic_ams_slave_panic_slave_id_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_slave_panic_ams_slave_panic_kind_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave_panic_ams_slave_panic_kind_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave_panic_ams_slave_panic_kind_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_ams_slave_panic_ams_slave_panic_arg_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_slave_panic_ams_slave_panic_arg_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_slave_panic_ams_slave_panic_arg_is_in_range(uint32_t value);
+
+/**
+ * Pack message AMS_In.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_ams_in_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_in_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AMS_In.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_ams_in_unpack(
+ struct can1__main_ft24_ams_in_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AMS_In.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_ams_in_init(struct can1__main_ft24_ams_in_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_in_ts_activate_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_in_ts_activate_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_in_ts_activate_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_in_inverters_discharged_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_in_inverters_discharged_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_in_inverters_discharged_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_ams_in_lap_number_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_ams_in_lap_number_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_ams_in_lap_number_is_in_range(uint8_t value);
+
+/**
+ * Pack message Shunt_Current.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_shunt_current_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_current_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Shunt_Current.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_shunt_current_unpack(
+ struct can1__main_ft24_shunt_current_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from Shunt_Current.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_shunt_current_init(struct can1__main_ft24_shunt_current_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int32_t can1__main_ft24_shunt_current_shunt_current_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_shunt_current_shunt_current_decode(int32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_shunt_current_shunt_current_is_in_range(int32_t value);
+
+/**
+ * Pack message Shunt_Voltage1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_shunt_voltage1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_voltage1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Shunt_Voltage1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_shunt_voltage1_unpack(
+ struct can1__main_ft24_shunt_voltage1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from Shunt_Voltage1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_shunt_voltage1_init(struct can1__main_ft24_shunt_voltage1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int32_t can1__main_ft24_shunt_voltage1_shunt_voltage1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_shunt_voltage1_shunt_voltage1_decode(int32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_shunt_voltage1_shunt_voltage1_is_in_range(int32_t value);
+
+/**
+ * Pack message Shunt_Voltage2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_shunt_voltage2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_voltage2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Shunt_Voltage2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_shunt_voltage2_unpack(
+ struct can1__main_ft24_shunt_voltage2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from Shunt_Voltage2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_shunt_voltage2_init(struct can1__main_ft24_shunt_voltage2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int32_t can1__main_ft24_shunt_voltage2_shunt_voltage2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_shunt_voltage2_shunt_voltage2_decode(int32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_shunt_voltage2_shunt_voltage2_is_in_range(int32_t value);
+
+/**
+ * Pack message Shunt_Voltage3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_shunt_voltage3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_voltage3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Shunt_Voltage3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_shunt_voltage3_unpack(
+ struct can1__main_ft24_shunt_voltage3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from Shunt_Voltage3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_shunt_voltage3_init(struct can1__main_ft24_shunt_voltage3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int32_t can1__main_ft24_shunt_voltage3_shunt_voltage3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_shunt_voltage3_shunt_voltage3_decode(int32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_shunt_voltage3_shunt_voltage3_is_in_range(int32_t value);
+
+/**
+ * Pack message Shunt_Temperature.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_shunt_temperature_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_temperature_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message Shunt_Temperature.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_shunt_temperature_unpack(
+ struct can1__main_ft24_shunt_temperature_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from Shunt_Temperature.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_shunt_temperature_init(struct can1__main_ft24_shunt_temperature_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_shunt_temperature_shunt_temperature_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_shunt_temperature_shunt_temperature_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_shunt_temperature_shunt_temperature_is_in_range(uint32_t value);
+
+/**
+ * Pack message SDCL_tx.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_sdcl_tx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_sdcl_tx_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message SDCL_tx.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_sdcl_tx_unpack(
+ struct can1__main_ft24_sdcl_tx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from SDCL_tx.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_sdcl_tx_init(struct can1__main_ft24_sdcl_tx_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_asms_state_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_asms_state_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_asms_state_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_sdc_state_1_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_sdc_state_1_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_sdc_state_1_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_sdc_state_2_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_sdc_state_2_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_sdc_state_2_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_sdc_state_3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_sdc_state_3_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_sdc_state_3_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_heartbeat_ok_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_heartbeat_ok_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_heartbeat_ok_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_sdcl_sdc_ready_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_sdcl_sdc_ready_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_sdcl_sdc_ready_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_ts_start_muxed_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_ts_start_muxed_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_ts_start_muxed_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_latch_init_open_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_latch_init_open_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_latch_init_open_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_latch_closed_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_latch_closed_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_latch_closed_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_latch_reopened_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_latch_reopened_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_latch_reopened_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_tx_as_mission_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_tx_as_mission_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_tx_as_mission_is_in_range(uint8_t value);
+
+/**
+ * Pack message SDCL_rx.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_sdcl_rx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_sdcl_rx_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message SDCL_rx.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_sdcl_rx_unpack(
+ struct can1__main_ft24_sdcl_rx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from SDCL_rx.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_sdcl_rx_init(struct can1__main_ft24_sdcl_rx_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_rx_as_close_sdc_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_rx_as_close_sdc_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_rx_as_close_sdc_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_rx_sdcl_heartbeat_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_rx_sdcl_heartbeat_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_rx_sdcl_heartbeat_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_rx_asb_error_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_rx_asb_error_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_rx_asb_error_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_sdcl_rx_as_mission_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_sdcl_rx_as_mission_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_sdcl_rx_as_mission_is_in_range(uint8_t value);
+
+/**
+ * Pack message PDU_Command.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_pdu_command_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_command_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message PDU_Command.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_pdu_command_unpack(
+ struct can1__main_ft24_pdu_command_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from PDU_Command.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_pdu_command_init(struct can1__main_ft24_pdu_command_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_inverter_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_inverter_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_inverter_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_mode_valve_2_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_mode_valve_2_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_mode_valve_2_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_ebs_valve_2_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_ebs_valve_2_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_ebs_valve_2_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_shutdown_circuit_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_shutdown_circuit_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_shutdown_circuit_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_alwayson_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_alwayson_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_alwayson_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_misc_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_misc_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_misc_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_servo_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_servo_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_servo_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_led1_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_led1_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_led1_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_led2_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_led2_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_led2_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_led3_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_led3_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_led3_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_sensorbox_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_sensorbox_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_sensorbox_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_service_brake_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_service_brake_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_service_brake_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_ebs_valve_1_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_ebs_valve_1_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_ebs_valve_1_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_steering_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_steering_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_steering_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_mode_valve_1_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_mode_valve_1_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_mode_valve_1_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_pwm_fans_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_pwm_fans_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_pwm_fans_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_pwm_aggregat_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_pwm_aggregat_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_pwm_aggregat_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_pwm_pump_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_pwm_pump_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_pwm_pump_rx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_command_pdu_checksum_rx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_command_pdu_checksum_rx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_command_pdu_checksum_rx_is_in_range(uint8_t value);
+
+/**
+ * Pack message PDU_Response.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_pdu_response_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_response_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message PDU_Response.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_pdu_response_unpack(
+ struct can1__main_ft24_pdu_response_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from PDU_Response.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_pdu_response_init(struct can1__main_ft24_pdu_response_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_inverter_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_inverter_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_inverter_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_mode_valve_2_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_mode_valve_2_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_mode_valve_2_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_evs_valve_2_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_evs_valve_2_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_evs_valve_2_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_shutdown_circuit_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_shutdown_circuit_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_shutdown_circuit_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_alwayson_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_alwayson_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_alwayson_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_misc_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_misc_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_misc_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_servo_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_servo_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_servo_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_led1_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_led1_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_led1_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_led2_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_led2_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_led2_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_led3_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_led3_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_led3_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_sensorbox_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_sensorbox_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_sensorbox_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_service_brake_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_service_brake_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_service_brake_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_ebs_valve_1_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_ebs_valve_1_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_ebs_valve_1_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_steering_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_steering_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_steering_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_mode_valve_1_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_mode_valve_1_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_mode_valve_1_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_pwm_fans_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_pwm_fans_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_pwm_fans_tx_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_pwm_aggregat_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_pwm_aggregat_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_pwm_aggregat_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_pwm_pump_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_pwm_pump_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_pwm_pump_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_pdu_response_pdu_checksum_tx_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_response_pdu_checksum_tx_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_response_pdu_checksum_tx_is_in_range(uint8_t value);
+
+/**
+ * Pack message TxPDO.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_tx_pdo_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tx_pdo_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message TxPDO.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_tx_pdo_unpack(
+ struct can1__main_ft24_tx_pdo_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from TxPDO.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_tx_pdo_init(struct can1__main_ft24_tx_pdo_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_powersupply_less_8v_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_powersupply_less_8v_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_powersupply_less_8v_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_powersupply_greater_32v_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_powersupply_greater_32v_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_powersupply_greater_32v_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_canbus_timeout_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_canbus_timeout_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_canbus_timeout_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_canbus_startupmissing_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_canbus_startupmissing_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_canbus_startupmissing_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_canbus_statewarning_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_canbus_statewarning_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_canbus_statewarning_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_middleposition_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_analoginput_middleposition_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_analoginput_middleposition_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_cablebreak_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_analoginput_cablebreak_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_analoginput_cablebreak_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_shortcircuit_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_analoginput_shortcircuit_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_analoginput_shortcircuit_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_currentoverload_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_analoginput_currentoverload_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_analoginput_currentoverload_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_temperature_warning_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_temperature_warning_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_temperature_warning_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_temperature_shutdown_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_temperature_shutdown_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_temperature_shutdown_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_output1_controllerrange_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_output1_controllerrange_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_output1_controllerrange_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_output2_controllerrange_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_output2_controllerrange_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_output2_controllerrange_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_output1_cablebreak_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_output1_cablebreak_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_output1_cablebreak_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_output2_cablebreak_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_output2_cablebreak_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_output2_cablebreak_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_output1_shortcircuit_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_output1_shortcircuit_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_output1_shortcircuit_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_tx_pdo_pdm_output2_shortcircuit_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_output2_shortcircuit_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_output2_shortcircuit_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_tx_pdo_pdm_analoginput_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_tx_pdo_pdm_analoginput_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_tx_pdo_pdm_analoginput_is_in_range(uint16_t value);
+
+/**
+ * Pack message XSens_Error.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_error_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_error_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_Error.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_error_unpack(
+ struct can1__main_ft24_x_sens_error_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_Error.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_error_init(struct can1__main_ft24_x_sens_error_t *msg_p);
+
+/**
+ * Pack message XSens_Warning.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_warning_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_warning_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_Warning.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_warning_unpack(
+ struct can1__main_ft24_x_sens_warning_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_Warning.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_warning_init(struct can1__main_ft24_x_sens_warning_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_warning_warning_code_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_warning_warning_code_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_warning_warning_code_is_in_range(uint8_t value);
+
+/**
+ * Pack message XSens_SampleTime.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_sample_time_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_sample_time_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_SampleTime.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_sample_time_unpack(
+ struct can1__main_ft24_x_sens_sample_time_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_SampleTime.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_sample_time_init(struct can1__main_ft24_x_sens_sample_time_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint32_t can1__main_ft24_x_sens_sample_time_timestamp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_sample_time_timestamp_decode(uint32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_sample_time_timestamp_is_in_range(uint32_t value);
+
+/**
+ * Pack message XSens_GroupCounter.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_group_counter_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_group_counter_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_GroupCounter.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_group_counter_unpack(
+ struct can1__main_ft24_x_sens_group_counter_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_GroupCounter.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_group_counter_init(struct can1__main_ft24_x_sens_group_counter_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_x_sens_group_counter_counter_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_group_counter_counter_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_group_counter_counter_is_in_range(uint16_t value);
+
+/**
+ * Pack message XSens_StatusWord.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_status_word_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_status_word_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_StatusWord.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_status_word_unpack(
+ struct can1__main_ft24_x_sens_status_word_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_StatusWord.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_status_word_init(struct can1__main_ft24_x_sens_status_word_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_have_gnss_time_pulse_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_have_gnss_time_pulse_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_have_gnss_time_pulse_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_rtk_status_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_rtk_status_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_rtk_status_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_filter_mode_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_filter_mode_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_filter_mode_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_mag_z_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_mag_z_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_mag_z_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_retransmitted_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_retransmitted_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_retransmitted_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clipping_detected_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clipping_detected_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clipping_detected_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_interpolated_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_interpolated_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_interpolated_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_sync_in_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_sync_in_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_sync_in_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_sync_out_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_sync_out_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_sync_out_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_acc_x_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_acc_x_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_acc_x_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_acc_y_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_acc_y_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_acc_y_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_acc_z_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_acc_z_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_acc_z_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_gyr_x_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_gyr_x_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_gyr_x_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_gyr_y_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_gyr_y_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_gyr_y_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_gyr_z_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_gyr_z_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_gyr_z_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_mag_x_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_mag_x_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_mag_x_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_clip_mag_y_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_clip_mag_y_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_clip_mag_y_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_self_test_ok_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_self_test_ok_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_self_test_ok_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_orientation_valid_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_orientation_valid_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_orientation_valid_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_gps_valid_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_gps_valid_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_gps_valid_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_no_rotation_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_no_rotation_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_no_rotation_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_representative_motion_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_representative_motion_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_representative_motion_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_x_sens_status_word_external_clock_synced_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_status_word_external_clock_synced_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_status_word_external_clock_synced_is_in_range(uint8_t value);
+
+/**
+ * Pack message XSens_RateOfTurn.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_rate_of_turn_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_rate_of_turn_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_RateOfTurn.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_rate_of_turn_unpack(
+ struct can1__main_ft24_x_sens_rate_of_turn_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_RateOfTurn.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_rate_of_turn_init(struct can1__main_ft24_x_sens_rate_of_turn_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_x_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_x_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_x_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_y_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_y_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_y_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_z_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_z_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_z_is_in_range(int16_t value);
+
+/**
+ * Pack message XSens_Acceleration.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_acceleration_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_acceleration_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_Acceleration.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_acceleration_unpack(
+ struct can1__main_ft24_x_sens_acceleration_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_Acceleration.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_acceleration_init(struct can1__main_ft24_x_sens_acceleration_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_acceleration_x_sens_acc_x_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_acceleration_x_sens_acc_x_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_acceleration_x_sens_acc_x_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_acceleration_x_sens_acc_y_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_acceleration_x_sens_acc_y_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_acceleration_x_sens_acc_y_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_acceleration_x_sens_acc_z_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_acceleration_x_sens_acc_z_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_acceleration_x_sens_acc_z_is_in_range(int16_t value);
+
+/**
+ * Pack message XSens_LongLat.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_long_lat_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_long_lat_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_LongLat.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_long_lat_unpack(
+ struct can1__main_ft24_x_sens_long_lat_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_LongLat.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_long_lat_init(struct can1__main_ft24_x_sens_long_lat_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int32_t can1__main_ft24_x_sens_long_lat_latitude_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_long_lat_latitude_decode(int32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_long_lat_latitude_is_in_range(int32_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int32_t can1__main_ft24_x_sens_long_lat_longitude_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_long_lat_longitude_decode(int32_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_long_lat_longitude_is_in_range(int32_t value);
+
+/**
+ * Pack message XSens_Velocity.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_x_sens_velocity_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_velocity_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message XSens_Velocity.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_x_sens_velocity_unpack(
+ struct can1__main_ft24_x_sens_velocity_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from XSens_Velocity.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_x_sens_velocity_init(struct can1__main_ft24_x_sens_velocity_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_velocity_vel_x_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_velocity_vel_x_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_velocity_vel_x_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_velocity_vel_y_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_velocity_vel_y_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_velocity_vel_y_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_x_sens_velocity_vel_z_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_x_sens_velocity_vel_z_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_x_sens_velocity_vel_z_is_in_range(int16_t value);
+
+/**
+ * Pack message AS_Mission_fb.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_as_mission_fb_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_as_mission_fb_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message AS_Mission_fb.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_as_mission_fb_unpack(
+ struct can1__main_ft24_as_mission_fb_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from AS_Mission_fb.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_as_mission_fb_init(struct can1__main_ft24_as_mission_fb_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_as_mission_fb_mission_selection_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_as_mission_fb_mission_selection_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_as_mission_fb_mission_selection_is_in_range(uint8_t value);
+
+/**
+ * Pack message STW_mission_selected.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_stw_mission_selected_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_mission_selected_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message STW_mission_selected.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_stw_mission_selected_unpack(
+ struct can1__main_ft24_stw_mission_selected_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from STW_mission_selected.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_stw_mission_selected_init(struct can1__main_ft24_stw_mission_selected_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_mission_selected_mission_selection_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_mission_selected_mission_selection_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_mission_selected_mission_selection_is_in_range(uint8_t value);
+
+/**
+ * Pack message EPSC_out.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_epsc_out_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_epsc_out_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message EPSC_out.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_epsc_out_unpack(
+ struct can1__main_ft24_epsc_out_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from EPSC_out.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_epsc_out_init(struct can1__main_ft24_epsc_out_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_epsc_out_epsc_measured_steering_angle_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_out_epsc_measured_steering_angle_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_out_epsc_measured_steering_angle_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_out_epsc_measured_current_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_out_epsc_measured_current_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_out_epsc_measured_current_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_out_epsc_measured_voltage_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_out_epsc_measured_voltage_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_out_epsc_measured_voltage_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_epsc_out_epsc_measured_rpm_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_out_epsc_measured_rpm_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_out_epsc_measured_rpm_is_in_range(int16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_epsc_out_epsc_measured_temperature_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_out_epsc_measured_temperature_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_out_epsc_measured_temperature_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_epsc_out_epsc_measured_internal_temp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_out_epsc_measured_internal_temp_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_out_epsc_measured_internal_temp_is_in_range(uint16_t value);
+
+/**
+ * Pack message EPSC_Steering_In.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_epsc_steering_in_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_epsc_steering_in_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message EPSC_Steering_In.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_epsc_steering_in_unpack(
+ struct can1__main_ft24_epsc_steering_in_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from EPSC_Steering_In.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_epsc_steering_in_init(struct can1__main_ft24_epsc_steering_in_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int16_t can1__main_ft24_epsc_steering_in_epsc_desired_steering_angle_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_steering_in_epsc_desired_steering_angle_decode(int16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_steering_in_epsc_desired_steering_angle_is_in_range(int16_t value);
+
+/**
+ * Pack message STW_buttons.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_stw_buttons_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_buttons_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message STW_buttons.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_stw_buttons_unpack(
+ struct can1__main_ft24_stw_buttons_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from STW_buttons.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_stw_buttons_init(struct can1__main_ft24_stw_buttons_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_buttons_stw_button_left_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_buttons_stw_button_left_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_buttons_stw_button_left_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_buttons_stw_button_right_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_buttons_stw_button_right_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_buttons_stw_button_right_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_buttons_stw_button_r2_d_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_buttons_stw_button_r2_d_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_buttons_stw_button_r2_d_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_buttons_stw_button_enter_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_buttons_stw_button_enter_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_buttons_stw_button_enter_is_in_range(uint8_t value);
+
+/**
+ * Pack message STW_status.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_stw_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_status_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message STW_status.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_stw_status_unpack(
+ struct can1__main_ft24_stw_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from STW_status.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_stw_status_init(struct can1__main_ft24_stw_status_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_as_state_stw_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_as_state_stw_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_as_state_stw_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_r2_d_progress_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_r2_d_progress_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_r2_d_progress_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_inv_l_ready_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_inv_l_ready_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_inv_l_ready_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_inv_r_ready_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_inv_r_ready_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_inv_r_ready_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_sdc_bfl_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_sdc_bfl_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_sdc_bfl_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_sdc_brl_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_sdc_brl_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_sdc_brl_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_sdc_acc_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_sdc_acc_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_sdc_acc_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_sdc_hvb_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_sdc_hvb_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_sdc_hvb_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_lap_count_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_lap_count_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_lap_count_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_ini_chk_state_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_ini_chk_state_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_ini_chk_state_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_sdc_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_sdc_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_sdc_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_ams_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_ams_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_ams_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_pdu_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_pdu_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_pdu_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_ini_chk_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_ini_chk_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_ini_chk_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_con_mon_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_con_mon_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_con_mon_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_scs_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_scs_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_scs_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_s_bspd_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_s_bspd_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_s_bspd_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_app_sp_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_app_sp_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_app_sp_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_as_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_as_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_as_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_ros_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_ros_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_ros_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_res_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_res_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_res_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_inv_l_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_inv_l_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_inv_l_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_stw_status_err_inv_r_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_stw_status_err_inv_r_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_stw_status_err_inv_r_is_in_range(uint8_t value);
+
+/**
+ * Pack message PDU_Current_1.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_pdu_current_1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_1_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message PDU_Current_1.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_pdu_current_1_unpack(
+ struct can1__main_ft24_pdu_current_1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from PDU_Current_1.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_pdu_current_1_init(struct can1__main_ft24_pdu_current_1_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_1_pdu_alwayson_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_1_pdu_alwayson_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_1_pdu_alwayson_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_1_pdu_misc_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_1_pdu_misc_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_1_pdu_misc_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_1_pdu_inverter_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_1_pdu_inverter_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_1_pdu_inverter_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_1_pdu_shutdown_circuit_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_1_pdu_shutdown_circuit_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_1_pdu_shutdown_circuit_curr_is_in_range(uint16_t value);
+
+/**
+ * Pack message PDU_Current_2.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_pdu_current_2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_2_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message PDU_Current_2.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_pdu_current_2_unpack(
+ struct can1__main_ft24_pdu_current_2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from PDU_Current_2.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_pdu_current_2_init(struct can1__main_ft24_pdu_current_2_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_2_pdu_fans_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_2_pdu_fans_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_2_pdu_fans_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_2_pdu_pump_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_2_pdu_pump_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_2_pdu_pump_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_2_pdu_aggregat_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_2_pdu_aggregat_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_2_pdu_aggregat_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_2_pdu_steering_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_2_pdu_steering_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_2_pdu_steering_curr_is_in_range(uint16_t value);
+
+/**
+ * Pack message PDU_Current_3.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_pdu_current_3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_3_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message PDU_Current_3.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_pdu_current_3_unpack(
+ struct can1__main_ft24_pdu_current_3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from PDU_Current_3.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_pdu_current_3_init(struct can1__main_ft24_pdu_current_3_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_3_pdu_ebs_valve_1_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_3_pdu_ebs_valve_1_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_3_pdu_ebs_valve_1_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_3_pdu_ebs_valve_2_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_3_pdu_ebs_valve_2_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_3_pdu_ebs_valve_2_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_3_pdu_mode_valve_1_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_3_pdu_mode_valve_1_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_3_pdu_mode_valve_1_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_3_pdu_mode_valve_2_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_3_pdu_mode_valve_2_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_3_pdu_mode_valve_2_curr_is_in_range(uint16_t value);
+
+/**
+ * Pack message PDU_Current_4.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_pdu_current_4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_4_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message PDU_Current_4.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_pdu_current_4_unpack(
+ struct can1__main_ft24_pdu_current_4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from PDU_Current_4.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_pdu_current_4_init(struct can1__main_ft24_pdu_current_4_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_4_pdu_sensorbox_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_4_pdu_sensorbox_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_4_pdu_sensorbox_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_4_pdu_service_brake_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_4_pdu_service_brake_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_4_pdu_service_brake_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_4_pdu_servos_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_4_pdu_servos_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_4_pdu_servos_curr_is_in_range(uint16_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint16_t can1__main_ft24_pdu_current_4_pdu_shutdown_circuit_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_pdu_current_4_pdu_shutdown_circuit_curr_decode(uint16_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_pdu_current_4_pdu_shutdown_circuit_curr_is_in_range(uint16_t value);
+
+/**
+ * Pack message EPSC_Config_In.
+ *
+ * @param[out] dst_p Buffer to pack the message into.
+ * @param[in] src_p Data to pack.
+ * @param[in] size Size of dst_p.
+ *
+ * @return Size of packed data, or negative error code.
+ */
+int can1__main_ft24_epsc_config_in_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_epsc_config_in_t *src_p,
+ size_t size);
+
+/**
+ * Unpack message EPSC_Config_In.
+ *
+ * @param[out] dst_p Object to unpack the message into.
+ * @param[in] src_p Message to unpack.
+ * @param[in] size Size of src_p.
+ *
+ * @return zero(0) or negative error code.
+ */
+int can1__main_ft24_epsc_config_in_unpack(
+ struct can1__main_ft24_epsc_config_in_t *dst_p,
+ const uint8_t *src_p,
+ size_t size);
+
+/**
+ * Init message fields to default values from EPSC_Config_In.
+ *
+ * @param[in] msg_p Message to init.
+ *
+ * @return zero(0) on success or (-1) in case of nullptr argument.
+ */
+int can1__main_ft24_epsc_config_in_init(struct can1__main_ft24_epsc_config_in_t *msg_p);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+int8_t can1__main_ft24_epsc_config_in_epsc_should_calibrate_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_should_calibrate_decode(int8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_should_calibrate_is_in_range(int8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_should_change_mode_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_should_change_mode_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_should_change_mode_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_mode_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_mode_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_mode_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag3_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_flag3_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_flag3_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag4_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_flag4_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_flag4_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag5_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_flag5_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_flag5_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag6_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_flag6_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_flag6_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag7_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_flag7_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_flag7_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_kp_pos_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_kp_pos_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_kp_pos_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_ki_pos_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_ki_pos_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_ki_pos_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_kp_rpm_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_kp_rpm_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_kp_rpm_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_ki_rpm_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_ki_rpm_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_ki_rpm_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_kp_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_kp_curr_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_kp_curr_is_in_range(uint8_t value);
+
+/**
+ * Encode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to encode.
+ *
+ * @return Encoded signal.
+ */
+uint8_t can1__main_ft24_epsc_config_in_epsc_ki_curr_encode(double value);
+
+/**
+ * Decode given signal by applying scaling and offset.
+ *
+ * @param[in] value Signal to decode.
+ *
+ * @return Decoded signal.
+ */
+double can1__main_ft24_epsc_config_in_epsc_ki_curr_decode(uint8_t value);
+
+/**
+ * Check that given signal is in allowed range.
+ *
+ * @param[in] value Signal to check.
+ *
+ * @return true if in range, false otherwise.
+ */
+bool can1__main_ft24_epsc_config_in_epsc_ki_curr_is_in_range(uint8_t value);
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/src/ros2_control_can/include/ros2_control_can/config.h b/src/ros2_control_can/include/ros2_control_can/config.h
index faf51c1..1753a17 100644
--- a/src/ros2_control_can/include/ros2_control_can/config.h
+++ b/src/ros2_control_can/include/ros2_control_can/config.h
@@ -6,13 +6,12 @@
struct Config
{
- std::string left_wheel_name = "left_wheel";
- std::string right_wheel_name = "right_wheel";
- float loop_rate = 30;
- std::string device = "/dev/ttyUSB0";
- int baud_rate = 115200;
- int timeout = 1000;
- int enc_counts_per_rev = 1920;
+ std::string front_left_wheel_name = "front_left_wheel";
+ std::string front_right_wheel_name = "front_right_wheel";
+ std::string rear_left_wheel_name = "rear_left_wheel";
+ std::string rear_right_wheel_name = "rear_right_wheel";
+ float loop_rate = 50;
+ std::string device = "vcan0";
};
diff --git a/src/ros2_control_can/include/ros2_control_can/ros2_control_can.h b/src/ros2_control_can/include/ros2_control_can/ros2_control_can.h
index 700d7a4..fc1b032 100644
--- a/src/ros2_control_can/include/ros2_control_can/ros2_control_can.h
+++ b/src/ros2_control_can/include/ros2_control_can/ros2_control_can.h
@@ -12,6 +12,7 @@
#include "config.h"
#include "wheel.h"
+#include "can1__main_ft24.h"
using hardware_interface::CallbackReturn;
using hardware_interface::return_type;
@@ -44,12 +45,20 @@ private:
Config cfg_;
- Wheel l_wheel_;
- Wheel r_wheel_;
+ Wheel f_l_wheel_;
+ Wheel f_r_wheel_;
+ Wheel r_l_wheel_;
+ Wheel r_r_wheel_;
+
+ can1__main_ft24_jetson_tx_t tx_frame;
+ can1__main_ft24_jetson_rx_t rx_frame;
+ uint8_t can_buffer[64];
rclcpp::Logger logger_;
std::chrono::time_point time_;
+
+ int socket_instance;
};
} // namespace ros2_control_can
diff --git a/src/ros2_control_can/include/ros2_control_can/wheel.h b/src/ros2_control_can/include/ros2_control_can/wheel.h
index f4c5d59..feeb89b 100644
--- a/src/ros2_control_can/include/ros2_control_can/wheel.h
+++ b/src/ros2_control_can/include/ros2_control_can/wheel.h
@@ -16,6 +16,7 @@ class Wheel
double vel = 0;
double eff = 0;
double velSetPt = 0;
+ double steer = 0;
Wheel() = default;
diff --git a/src/ros2_control_can/package.xml b/src/ros2_control_can/package.xml
index 06f8dc5..c982f87 100644
--- a/src/ros2_control_can/package.xml
+++ b/src/ros2_control_can/package.xml
@@ -4,9 +4,12 @@
0.0.1
Provides an interface between ROS2_control and a CAN device.
- Tim Korjakow
- Tim Korjakow
- BSD
+ Tim Korjakow
+ Tim Korjakow
+ Todo
+
+ ros2_control
+ ros2_controllers
ament_cmake
@@ -18,7 +21,6 @@
-ament_add_gmock
hardware_interface
diff --git a/src/ros2_control_can/src/can1__main_ft24.cpp b/src/ros2_control_can/src/can1__main_ft24.cpp
new file mode 100644
index 0000000..a91cb83
--- /dev/null
+++ b/src/ros2_control_can/src/can1__main_ft24.cpp
@@ -0,0 +1,33719 @@
+/**
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Erik Moqvist
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+/**
+ * This file was generated by cantools version 39.3.0 Mon Nov 27 15:11:10 2023.
+ */
+
+#include
+
+#include "can1__main_ft24.h"
+
+static inline uint8_t pack_left_shift_u8(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value << shift) & mask);
+}
+
+static inline uint8_t pack_left_shift_u16(
+ uint16_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value << shift) & mask);
+}
+
+static inline uint8_t pack_left_shift_u32(
+ uint32_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value << shift) & mask);
+}
+
+static inline uint8_t pack_right_shift_u8(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value >> shift) & mask);
+}
+
+static inline uint8_t pack_right_shift_u16(
+ uint16_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value >> shift) & mask);
+}
+
+static inline uint8_t pack_right_shift_u32(
+ uint32_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value >> shift) & mask);
+}
+
+static inline uint8_t unpack_left_shift_u8(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value & mask) << shift);
+}
+
+static inline uint16_t unpack_left_shift_u16(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint16_t)((uint16_t)(value & mask) << shift);
+}
+
+static inline uint32_t unpack_left_shift_u32(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint32_t)((uint32_t)(value & mask) << shift);
+}
+
+static inline uint8_t unpack_right_shift_u8(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint8_t)((uint8_t)(value & mask) >> shift);
+}
+
+static inline uint16_t unpack_right_shift_u16(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint16_t)((uint16_t)(value & mask) >> shift);
+}
+
+static inline uint32_t unpack_right_shift_u32(
+ uint8_t value,
+ uint8_t shift,
+ uint8_t mask)
+{
+ return (uint32_t)((uint32_t)(value & mask) >> shift);
+}
+
+int can1__main_ft24_abx_param_confirm_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_param_confirm_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->abx_param_confirm, 0u, 0xffu);
+
+ return (1);
+}
+
+int can1__main_ft24_abx_param_confirm_unpack(
+ struct can1__main_ft24_abx_param_confirm_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_param_confirm = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_param_confirm_init(struct can1__main_ft24_abx_param_confirm_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_param_confirm_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_abx_param_confirm_abx_param_confirm_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_abx_param_confirm_abx_param_confirm_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_param_confirm_abx_param_confirm_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_abx_hydraulics_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_hydraulics_t *src_p,
+ size_t size)
+{
+ if (size < 3u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 3);
+
+ dst_p[0] |= pack_left_shift_u16(src_p->abx_hyd_pa, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(src_p->abx_hyd_pa, 8u, 0x0fu);
+ dst_p[1] |= pack_left_shift_u16(src_p->abx_hyd_pb, 4u, 0xf0u);
+ dst_p[2] |= pack_right_shift_u16(src_p->abx_hyd_pb, 4u, 0xffu);
+
+ return (3);
+}
+
+int can1__main_ft24_abx_hydraulics_unpack(
+ struct can1__main_ft24_abx_hydraulics_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 3u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_hyd_pa = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ dst_p->abx_hyd_pa |= unpack_left_shift_u16(src_p[1], 8u, 0x0fu);
+ dst_p->abx_hyd_pb = unpack_right_shift_u16(src_p[1], 4u, 0xf0u);
+ dst_p->abx_hyd_pb |= unpack_left_shift_u16(src_p[2], 4u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_hydraulics_init(struct can1__main_ft24_abx_hydraulics_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_hydraulics_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_abx_hydraulics_abx_hyd_pa_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_hydraulics_abx_hyd_pa_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_hydraulics_abx_hyd_pa_is_in_range(uint16_t value)
+{
+ return (value <= 4095u);
+}
+
+uint16_t can1__main_ft24_abx_hydraulics_abx_hyd_pb_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_hydraulics_abx_hyd_pb_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_hydraulics_abx_hyd_pb_is_in_range(uint16_t value)
+{
+ return (value <= 4095u);
+}
+
+int can1__main_ft24_jetson_tx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_jetson_tx_t *src_p,
+ size_t size)
+{
+ uint8_t jetson_steering_angle;
+
+ if (size < 7u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 7);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_as_mission_complete, 0u, 0x01u);
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_as_ok, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_lap_count, 4u, 0xf0u);
+ dst_p[1] |= pack_left_shift_u8(src_p->jetson_speed_target, 0u, 0xffu);
+ jetson_steering_angle = (uint8_t)src_p->jetson_steering_angle;
+ dst_p[2] |= pack_left_shift_u8(jetson_steering_angle, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->jetson_brake_ratio, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->jetson_torque_ratio, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->jetson_cones_all, 0u, 0xffu);
+ dst_p[6] |= pack_left_shift_u8(src_p->jetson_cones_actual, 0u, 0xffu);
+
+ return (7);
+}
+
+int can1__main_ft24_jetson_tx_unpack(
+ struct can1__main_ft24_jetson_tx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t jetson_steering_angle;
+
+ if (size < 7u) {
+ return (-EINVAL);
+ }
+
+ dst_p->jetson_as_mission_complete = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
+ dst_p->jetson_as_ok = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->jetson_lap_count = unpack_right_shift_u8(src_p[0], 4u, 0xf0u);
+ dst_p->jetson_speed_target = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ jetson_steering_angle = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->jetson_steering_angle = (int8_t)jetson_steering_angle;
+ dst_p->jetson_brake_ratio = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->jetson_torque_ratio = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->jetson_cones_all = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->jetson_cones_actual = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_jetson_tx_init(struct can1__main_ft24_jetson_tx_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_jetson_tx_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_as_mission_complete_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_tx_jetson_as_mission_complete_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_as_mission_complete_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_as_ok_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_tx_jetson_as_ok_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_as_ok_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_lap_count_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_tx_jetson_lap_count_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_lap_count_is_in_range(uint8_t value)
+{
+ return (value <= 15u);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_speed_target_encode(double value)
+{
+ return (uint8_t)(value / 0.2);
+}
+
+double can1__main_ft24_jetson_tx_jetson_speed_target_decode(uint8_t value)
+{
+ return ((double)value * 0.2);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_speed_target_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_jetson_tx_jetson_steering_angle_encode(double value)
+{
+ return (int8_t)(value / 0.00784313725490196);
+}
+
+double can1__main_ft24_jetson_tx_jetson_steering_angle_decode(int8_t value)
+{
+ return ((double)value * 0.00784313725490196);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_steering_angle_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_brake_ratio_encode(double value)
+{
+ return (uint8_t)(value / 0.00392156862745098);
+}
+
+double can1__main_ft24_jetson_tx_jetson_brake_ratio_decode(uint8_t value)
+{
+ return ((double)value * 0.00392156862745098);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_brake_ratio_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_torque_ratio_encode(double value)
+{
+ return (uint8_t)(value / 0.00392156862745098);
+}
+
+double can1__main_ft24_jetson_tx_jetson_torque_ratio_decode(uint8_t value)
+{
+ return ((double)value * 0.00392156862745098);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_torque_ratio_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_cones_all_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_tx_jetson_cones_all_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_cones_all_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_jetson_tx_jetson_cones_actual_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_tx_jetson_cones_actual_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_tx_jetson_cones_actual_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave0_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave0_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave0_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave0_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave0_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave0_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave0_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave0_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log0_unpack(
+ struct can1__main_ft24_ams_slave0_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave0_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave0_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave0_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave0_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave0_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log0_init(struct can1__main_ft24_ams_slave0_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log0_ams_slave0_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log0_ams_slave0_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log0_ams_slave0_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave0_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave0_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave0_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave0_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave0_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave0_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave0_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave0_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log1_unpack(
+ struct can1__main_ft24_ams_slave0_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave0_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave0_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave0_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave0_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave0_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log1_init(struct can1__main_ft24_ams_slave0_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log1_ams_slave0_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log1_ams_slave0_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log1_ams_slave0_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave0_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave0_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave0_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave0_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave0_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave0_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave0_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave0_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log2_unpack(
+ struct can1__main_ft24_ams_slave0_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave0_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave0_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave0_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave0_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave0_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log2_init(struct can1__main_ft24_ams_slave0_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log2_ams_slave0_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log2_ams_slave0_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log2_ams_slave0_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave0_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave0_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave0_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave0_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave0_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave0_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave0_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave0_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log3_unpack(
+ struct can1__main_ft24_ams_slave0_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave0_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave0_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave0_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave0_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave0_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log3_init(struct can1__main_ft24_ams_slave0_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave0_log3_ams_slave0_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log3_ams_slave0_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log3_ams_slave0_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave0_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave0_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave0_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave0_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave0_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave0_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave0_log4_unpack(
+ struct can1__main_ft24_ams_slave0_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave0_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave0_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave0_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave0_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave0_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log4_init(struct can1__main_ft24_ams_slave0_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave0_log4_ams_slave0_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_log4_ams_slave0_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_log4_ams_slave0_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave0_log4_ams_slave0_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log4_ams_slave0_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log4_ams_slave0_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t0;
+ uint8_t ams_slave0_t1;
+ uint8_t ams_slave0_t2;
+ uint8_t ams_slave0_t3;
+ uint8_t ams_slave0_t4;
+ uint8_t ams_slave0_t5;
+ uint8_t ams_slave0_t6;
+ uint8_t ams_slave0_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave0_t0 = (uint8_t)src_p->ams_slave0_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave0_t0, 0u, 0xffu);
+ ams_slave0_t1 = (uint8_t)src_p->ams_slave0_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave0_t1, 0u, 0xffu);
+ ams_slave0_t2 = (uint8_t)src_p->ams_slave0_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave0_t2, 0u, 0xffu);
+ ams_slave0_t3 = (uint8_t)src_p->ams_slave0_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave0_t3, 0u, 0xffu);
+ ams_slave0_t4 = (uint8_t)src_p->ams_slave0_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave0_t4, 0u, 0xffu);
+ ams_slave0_t5 = (uint8_t)src_p->ams_slave0_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave0_t5, 0u, 0xffu);
+ ams_slave0_t6 = (uint8_t)src_p->ams_slave0_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave0_t6, 0u, 0xffu);
+ ams_slave0_t7 = (uint8_t)src_p->ams_slave0_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave0_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log5_unpack(
+ struct can1__main_ft24_ams_slave0_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t0;
+ uint8_t ams_slave0_t1;
+ uint8_t ams_slave0_t2;
+ uint8_t ams_slave0_t3;
+ uint8_t ams_slave0_t4;
+ uint8_t ams_slave0_t5;
+ uint8_t ams_slave0_t6;
+ uint8_t ams_slave0_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave0_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave0_t0 = (int8_t)ams_slave0_t0;
+ ams_slave0_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_t1 = (int8_t)ams_slave0_t1;
+ ams_slave0_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave0_t2 = (int8_t)ams_slave0_t2;
+ ams_slave0_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_t3 = (int8_t)ams_slave0_t3;
+ ams_slave0_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave0_t4 = (int8_t)ams_slave0_t4;
+ ams_slave0_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_t5 = (int8_t)ams_slave0_t5;
+ ams_slave0_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave0_t6 = (int8_t)ams_slave0_t6;
+ ams_slave0_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave0_t7 = (int8_t)ams_slave0_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log5_init(struct can1__main_ft24_ams_slave0_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log5_ams_slave0_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log5_ams_slave0_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log5_ams_slave0_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t10;
+ uint8_t ams_slave0_t11;
+ uint8_t ams_slave0_t12;
+ uint8_t ams_slave0_t13;
+ uint8_t ams_slave0_t14;
+ uint8_t ams_slave0_t15;
+ uint8_t ams_slave0_t8;
+ uint8_t ams_slave0_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave0_t8 = (uint8_t)src_p->ams_slave0_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave0_t8, 0u, 0xffu);
+ ams_slave0_t9 = (uint8_t)src_p->ams_slave0_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave0_t9, 0u, 0xffu);
+ ams_slave0_t10 = (uint8_t)src_p->ams_slave0_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave0_t10, 0u, 0xffu);
+ ams_slave0_t11 = (uint8_t)src_p->ams_slave0_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave0_t11, 0u, 0xffu);
+ ams_slave0_t12 = (uint8_t)src_p->ams_slave0_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave0_t12, 0u, 0xffu);
+ ams_slave0_t13 = (uint8_t)src_p->ams_slave0_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave0_t13, 0u, 0xffu);
+ ams_slave0_t14 = (uint8_t)src_p->ams_slave0_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave0_t14, 0u, 0xffu);
+ ams_slave0_t15 = (uint8_t)src_p->ams_slave0_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave0_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log6_unpack(
+ struct can1__main_ft24_ams_slave0_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t10;
+ uint8_t ams_slave0_t11;
+ uint8_t ams_slave0_t12;
+ uint8_t ams_slave0_t13;
+ uint8_t ams_slave0_t14;
+ uint8_t ams_slave0_t15;
+ uint8_t ams_slave0_t8;
+ uint8_t ams_slave0_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave0_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave0_t8 = (int8_t)ams_slave0_t8;
+ ams_slave0_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_t9 = (int8_t)ams_slave0_t9;
+ ams_slave0_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave0_t10 = (int8_t)ams_slave0_t10;
+ ams_slave0_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_t11 = (int8_t)ams_slave0_t11;
+ ams_slave0_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave0_t12 = (int8_t)ams_slave0_t12;
+ ams_slave0_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_t13 = (int8_t)ams_slave0_t13;
+ ams_slave0_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave0_t14 = (int8_t)ams_slave0_t14;
+ ams_slave0_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave0_t15 = (int8_t)ams_slave0_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log6_init(struct can1__main_ft24_ams_slave0_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log6_ams_slave0_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log6_ams_slave0_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log6_ams_slave0_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t16;
+ uint8_t ams_slave0_t17;
+ uint8_t ams_slave0_t18;
+ uint8_t ams_slave0_t19;
+ uint8_t ams_slave0_t20;
+ uint8_t ams_slave0_t21;
+ uint8_t ams_slave0_t22;
+ uint8_t ams_slave0_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave0_t16 = (uint8_t)src_p->ams_slave0_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave0_t16, 0u, 0xffu);
+ ams_slave0_t17 = (uint8_t)src_p->ams_slave0_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave0_t17, 0u, 0xffu);
+ ams_slave0_t18 = (uint8_t)src_p->ams_slave0_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave0_t18, 0u, 0xffu);
+ ams_slave0_t19 = (uint8_t)src_p->ams_slave0_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave0_t19, 0u, 0xffu);
+ ams_slave0_t20 = (uint8_t)src_p->ams_slave0_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave0_t20, 0u, 0xffu);
+ ams_slave0_t21 = (uint8_t)src_p->ams_slave0_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave0_t21, 0u, 0xffu);
+ ams_slave0_t22 = (uint8_t)src_p->ams_slave0_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave0_t22, 0u, 0xffu);
+ ams_slave0_t23 = (uint8_t)src_p->ams_slave0_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave0_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log7_unpack(
+ struct can1__main_ft24_ams_slave0_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t16;
+ uint8_t ams_slave0_t17;
+ uint8_t ams_slave0_t18;
+ uint8_t ams_slave0_t19;
+ uint8_t ams_slave0_t20;
+ uint8_t ams_slave0_t21;
+ uint8_t ams_slave0_t22;
+ uint8_t ams_slave0_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave0_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave0_t16 = (int8_t)ams_slave0_t16;
+ ams_slave0_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_t17 = (int8_t)ams_slave0_t17;
+ ams_slave0_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave0_t18 = (int8_t)ams_slave0_t18;
+ ams_slave0_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_t19 = (int8_t)ams_slave0_t19;
+ ams_slave0_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave0_t20 = (int8_t)ams_slave0_t20;
+ ams_slave0_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_t21 = (int8_t)ams_slave0_t21;
+ ams_slave0_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave0_t22 = (int8_t)ams_slave0_t22;
+ ams_slave0_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave0_t23 = (int8_t)ams_slave0_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log7_init(struct can1__main_ft24_ams_slave0_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log7_ams_slave0_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log7_ams_slave0_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log7_ams_slave0_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave0_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t24;
+ uint8_t ams_slave0_t25;
+ uint8_t ams_slave0_t26;
+ uint8_t ams_slave0_t27;
+ uint8_t ams_slave0_t28;
+ uint8_t ams_slave0_t29;
+ uint8_t ams_slave0_t30;
+ uint8_t ams_slave0_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave0_t24 = (uint8_t)src_p->ams_slave0_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave0_t24, 0u, 0xffu);
+ ams_slave0_t25 = (uint8_t)src_p->ams_slave0_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave0_t25, 0u, 0xffu);
+ ams_slave0_t26 = (uint8_t)src_p->ams_slave0_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave0_t26, 0u, 0xffu);
+ ams_slave0_t27 = (uint8_t)src_p->ams_slave0_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave0_t27, 0u, 0xffu);
+ ams_slave0_t28 = (uint8_t)src_p->ams_slave0_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave0_t28, 0u, 0xffu);
+ ams_slave0_t29 = (uint8_t)src_p->ams_slave0_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave0_t29, 0u, 0xffu);
+ ams_slave0_t30 = (uint8_t)src_p->ams_slave0_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave0_t30, 0u, 0xffu);
+ ams_slave0_t31 = (uint8_t)src_p->ams_slave0_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave0_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_log8_unpack(
+ struct can1__main_ft24_ams_slave0_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave0_t24;
+ uint8_t ams_slave0_t25;
+ uint8_t ams_slave0_t26;
+ uint8_t ams_slave0_t27;
+ uint8_t ams_slave0_t28;
+ uint8_t ams_slave0_t29;
+ uint8_t ams_slave0_t30;
+ uint8_t ams_slave0_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave0_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave0_t24 = (int8_t)ams_slave0_t24;
+ ams_slave0_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave0_t25 = (int8_t)ams_slave0_t25;
+ ams_slave0_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave0_t26 = (int8_t)ams_slave0_t26;
+ ams_slave0_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave0_t27 = (int8_t)ams_slave0_t27;
+ ams_slave0_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave0_t28 = (int8_t)ams_slave0_t28;
+ ams_slave0_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave0_t29 = (int8_t)ams_slave0_t29;
+ ams_slave0_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave0_t30 = (int8_t)ams_slave0_t30;
+ ams_slave0_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave0_t31 = (int8_t)ams_slave0_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_log8_init(struct can1__main_ft24_ams_slave0_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave0_log8_ams_slave0_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_log8_ams_slave0_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_log8_ams_slave0_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave1_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave1_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave1_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave1_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave1_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave1_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave1_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave1_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log0_unpack(
+ struct can1__main_ft24_ams_slave1_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave1_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave1_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave1_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave1_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave1_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log0_init(struct can1__main_ft24_ams_slave1_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log0_ams_slave1_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log0_ams_slave1_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log0_ams_slave1_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave1_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave1_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave1_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave1_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave1_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave1_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave1_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave1_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log1_unpack(
+ struct can1__main_ft24_ams_slave1_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave1_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave1_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave1_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave1_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave1_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log1_init(struct can1__main_ft24_ams_slave1_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log1_ams_slave1_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log1_ams_slave1_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log1_ams_slave1_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave1_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave1_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave1_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave1_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave1_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave1_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave1_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave1_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log2_unpack(
+ struct can1__main_ft24_ams_slave1_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave1_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave1_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave1_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave1_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave1_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log2_init(struct can1__main_ft24_ams_slave1_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log2_ams_slave1_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log2_ams_slave1_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log2_ams_slave1_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave1_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave1_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave1_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave1_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave1_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave1_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave1_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave1_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log3_unpack(
+ struct can1__main_ft24_ams_slave1_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave1_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave1_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave1_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave1_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave1_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log3_init(struct can1__main_ft24_ams_slave1_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave1_log3_ams_slave1_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log3_ams_slave1_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log3_ams_slave1_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave1_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave1_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave1_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave1_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave1_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave1_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave1_log4_unpack(
+ struct can1__main_ft24_ams_slave1_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave1_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave1_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave1_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave1_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave1_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log4_init(struct can1__main_ft24_ams_slave1_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave1_log4_ams_slave1_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_log4_ams_slave1_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_log4_ams_slave1_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave1_log4_ams_slave1_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log4_ams_slave1_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log4_ams_slave1_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t0;
+ uint8_t ams_slave1_t1;
+ uint8_t ams_slave1_t2;
+ uint8_t ams_slave1_t3;
+ uint8_t ams_slave1_t4;
+ uint8_t ams_slave1_t5;
+ uint8_t ams_slave1_t6;
+ uint8_t ams_slave1_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave1_t0 = (uint8_t)src_p->ams_slave1_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave1_t0, 0u, 0xffu);
+ ams_slave1_t1 = (uint8_t)src_p->ams_slave1_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave1_t1, 0u, 0xffu);
+ ams_slave1_t2 = (uint8_t)src_p->ams_slave1_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave1_t2, 0u, 0xffu);
+ ams_slave1_t3 = (uint8_t)src_p->ams_slave1_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave1_t3, 0u, 0xffu);
+ ams_slave1_t4 = (uint8_t)src_p->ams_slave1_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave1_t4, 0u, 0xffu);
+ ams_slave1_t5 = (uint8_t)src_p->ams_slave1_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave1_t5, 0u, 0xffu);
+ ams_slave1_t6 = (uint8_t)src_p->ams_slave1_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave1_t6, 0u, 0xffu);
+ ams_slave1_t7 = (uint8_t)src_p->ams_slave1_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave1_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log5_unpack(
+ struct can1__main_ft24_ams_slave1_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t0;
+ uint8_t ams_slave1_t1;
+ uint8_t ams_slave1_t2;
+ uint8_t ams_slave1_t3;
+ uint8_t ams_slave1_t4;
+ uint8_t ams_slave1_t5;
+ uint8_t ams_slave1_t6;
+ uint8_t ams_slave1_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave1_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave1_t0 = (int8_t)ams_slave1_t0;
+ ams_slave1_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_t1 = (int8_t)ams_slave1_t1;
+ ams_slave1_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave1_t2 = (int8_t)ams_slave1_t2;
+ ams_slave1_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_t3 = (int8_t)ams_slave1_t3;
+ ams_slave1_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave1_t4 = (int8_t)ams_slave1_t4;
+ ams_slave1_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_t5 = (int8_t)ams_slave1_t5;
+ ams_slave1_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave1_t6 = (int8_t)ams_slave1_t6;
+ ams_slave1_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave1_t7 = (int8_t)ams_slave1_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log5_init(struct can1__main_ft24_ams_slave1_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log5_ams_slave1_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log5_ams_slave1_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log5_ams_slave1_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t10;
+ uint8_t ams_slave1_t11;
+ uint8_t ams_slave1_t12;
+ uint8_t ams_slave1_t13;
+ uint8_t ams_slave1_t14;
+ uint8_t ams_slave1_t15;
+ uint8_t ams_slave1_t8;
+ uint8_t ams_slave1_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave1_t8 = (uint8_t)src_p->ams_slave1_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave1_t8, 0u, 0xffu);
+ ams_slave1_t9 = (uint8_t)src_p->ams_slave1_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave1_t9, 0u, 0xffu);
+ ams_slave1_t10 = (uint8_t)src_p->ams_slave1_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave1_t10, 0u, 0xffu);
+ ams_slave1_t11 = (uint8_t)src_p->ams_slave1_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave1_t11, 0u, 0xffu);
+ ams_slave1_t12 = (uint8_t)src_p->ams_slave1_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave1_t12, 0u, 0xffu);
+ ams_slave1_t13 = (uint8_t)src_p->ams_slave1_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave1_t13, 0u, 0xffu);
+ ams_slave1_t14 = (uint8_t)src_p->ams_slave1_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave1_t14, 0u, 0xffu);
+ ams_slave1_t15 = (uint8_t)src_p->ams_slave1_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave1_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log6_unpack(
+ struct can1__main_ft24_ams_slave1_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t10;
+ uint8_t ams_slave1_t11;
+ uint8_t ams_slave1_t12;
+ uint8_t ams_slave1_t13;
+ uint8_t ams_slave1_t14;
+ uint8_t ams_slave1_t15;
+ uint8_t ams_slave1_t8;
+ uint8_t ams_slave1_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave1_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave1_t8 = (int8_t)ams_slave1_t8;
+ ams_slave1_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_t9 = (int8_t)ams_slave1_t9;
+ ams_slave1_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave1_t10 = (int8_t)ams_slave1_t10;
+ ams_slave1_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_t11 = (int8_t)ams_slave1_t11;
+ ams_slave1_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave1_t12 = (int8_t)ams_slave1_t12;
+ ams_slave1_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_t13 = (int8_t)ams_slave1_t13;
+ ams_slave1_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave1_t14 = (int8_t)ams_slave1_t14;
+ ams_slave1_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave1_t15 = (int8_t)ams_slave1_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log6_init(struct can1__main_ft24_ams_slave1_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log6_ams_slave1_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log6_ams_slave1_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log6_ams_slave1_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t16;
+ uint8_t ams_slave1_t17;
+ uint8_t ams_slave1_t18;
+ uint8_t ams_slave1_t19;
+ uint8_t ams_slave1_t20;
+ uint8_t ams_slave1_t21;
+ uint8_t ams_slave1_t22;
+ uint8_t ams_slave1_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave1_t16 = (uint8_t)src_p->ams_slave1_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave1_t16, 0u, 0xffu);
+ ams_slave1_t17 = (uint8_t)src_p->ams_slave1_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave1_t17, 0u, 0xffu);
+ ams_slave1_t18 = (uint8_t)src_p->ams_slave1_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave1_t18, 0u, 0xffu);
+ ams_slave1_t19 = (uint8_t)src_p->ams_slave1_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave1_t19, 0u, 0xffu);
+ ams_slave1_t20 = (uint8_t)src_p->ams_slave1_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave1_t20, 0u, 0xffu);
+ ams_slave1_t21 = (uint8_t)src_p->ams_slave1_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave1_t21, 0u, 0xffu);
+ ams_slave1_t22 = (uint8_t)src_p->ams_slave1_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave1_t22, 0u, 0xffu);
+ ams_slave1_t23 = (uint8_t)src_p->ams_slave1_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave1_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log7_unpack(
+ struct can1__main_ft24_ams_slave1_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t16;
+ uint8_t ams_slave1_t17;
+ uint8_t ams_slave1_t18;
+ uint8_t ams_slave1_t19;
+ uint8_t ams_slave1_t20;
+ uint8_t ams_slave1_t21;
+ uint8_t ams_slave1_t22;
+ uint8_t ams_slave1_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave1_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave1_t16 = (int8_t)ams_slave1_t16;
+ ams_slave1_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_t17 = (int8_t)ams_slave1_t17;
+ ams_slave1_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave1_t18 = (int8_t)ams_slave1_t18;
+ ams_slave1_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_t19 = (int8_t)ams_slave1_t19;
+ ams_slave1_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave1_t20 = (int8_t)ams_slave1_t20;
+ ams_slave1_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_t21 = (int8_t)ams_slave1_t21;
+ ams_slave1_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave1_t22 = (int8_t)ams_slave1_t22;
+ ams_slave1_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave1_t23 = (int8_t)ams_slave1_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log7_init(struct can1__main_ft24_ams_slave1_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log7_ams_slave1_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log7_ams_slave1_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log7_ams_slave1_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave1_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t24;
+ uint8_t ams_slave1_t25;
+ uint8_t ams_slave1_t26;
+ uint8_t ams_slave1_t27;
+ uint8_t ams_slave1_t28;
+ uint8_t ams_slave1_t29;
+ uint8_t ams_slave1_t30;
+ uint8_t ams_slave1_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave1_t24 = (uint8_t)src_p->ams_slave1_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave1_t24, 0u, 0xffu);
+ ams_slave1_t25 = (uint8_t)src_p->ams_slave1_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave1_t25, 0u, 0xffu);
+ ams_slave1_t26 = (uint8_t)src_p->ams_slave1_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave1_t26, 0u, 0xffu);
+ ams_slave1_t27 = (uint8_t)src_p->ams_slave1_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave1_t27, 0u, 0xffu);
+ ams_slave1_t28 = (uint8_t)src_p->ams_slave1_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave1_t28, 0u, 0xffu);
+ ams_slave1_t29 = (uint8_t)src_p->ams_slave1_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave1_t29, 0u, 0xffu);
+ ams_slave1_t30 = (uint8_t)src_p->ams_slave1_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave1_t30, 0u, 0xffu);
+ ams_slave1_t31 = (uint8_t)src_p->ams_slave1_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave1_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_log8_unpack(
+ struct can1__main_ft24_ams_slave1_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave1_t24;
+ uint8_t ams_slave1_t25;
+ uint8_t ams_slave1_t26;
+ uint8_t ams_slave1_t27;
+ uint8_t ams_slave1_t28;
+ uint8_t ams_slave1_t29;
+ uint8_t ams_slave1_t30;
+ uint8_t ams_slave1_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave1_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave1_t24 = (int8_t)ams_slave1_t24;
+ ams_slave1_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave1_t25 = (int8_t)ams_slave1_t25;
+ ams_slave1_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave1_t26 = (int8_t)ams_slave1_t26;
+ ams_slave1_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave1_t27 = (int8_t)ams_slave1_t27;
+ ams_slave1_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave1_t28 = (int8_t)ams_slave1_t28;
+ ams_slave1_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave1_t29 = (int8_t)ams_slave1_t29;
+ ams_slave1_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave1_t30 = (int8_t)ams_slave1_t30;
+ ams_slave1_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave1_t31 = (int8_t)ams_slave1_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_log8_init(struct can1__main_ft24_ams_slave1_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave1_log8_ams_slave1_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_log8_ams_slave1_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_log8_ams_slave1_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave2_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave2_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave2_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave2_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave2_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave2_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave2_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave2_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log0_unpack(
+ struct can1__main_ft24_ams_slave2_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave2_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave2_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave2_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave2_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave2_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log0_init(struct can1__main_ft24_ams_slave2_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log0_ams_slave2_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log0_ams_slave2_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log0_ams_slave2_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave2_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave2_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave2_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave2_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave2_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave2_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave2_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave2_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log1_unpack(
+ struct can1__main_ft24_ams_slave2_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave2_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave2_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave2_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave2_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave2_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log1_init(struct can1__main_ft24_ams_slave2_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log1_ams_slave2_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log1_ams_slave2_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log1_ams_slave2_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave2_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave2_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave2_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave2_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave2_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave2_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave2_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave2_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log2_unpack(
+ struct can1__main_ft24_ams_slave2_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave2_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave2_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave2_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave2_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave2_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log2_init(struct can1__main_ft24_ams_slave2_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log2_ams_slave2_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log2_ams_slave2_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log2_ams_slave2_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave2_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave2_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave2_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave2_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave2_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave2_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave2_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave2_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log3_unpack(
+ struct can1__main_ft24_ams_slave2_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave2_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave2_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave2_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave2_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave2_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log3_init(struct can1__main_ft24_ams_slave2_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave2_log3_ams_slave2_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log3_ams_slave2_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log3_ams_slave2_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave2_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave2_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave2_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave2_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave2_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave2_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave2_log4_unpack(
+ struct can1__main_ft24_ams_slave2_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave2_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave2_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave2_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave2_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave2_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log4_init(struct can1__main_ft24_ams_slave2_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave2_log4_ams_slave2_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_log4_ams_slave2_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_log4_ams_slave2_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave2_log4_ams_slave2_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log4_ams_slave2_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log4_ams_slave2_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t0;
+ uint8_t ams_slave2_t1;
+ uint8_t ams_slave2_t2;
+ uint8_t ams_slave2_t3;
+ uint8_t ams_slave2_t4;
+ uint8_t ams_slave2_t5;
+ uint8_t ams_slave2_t6;
+ uint8_t ams_slave2_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave2_t0 = (uint8_t)src_p->ams_slave2_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave2_t0, 0u, 0xffu);
+ ams_slave2_t1 = (uint8_t)src_p->ams_slave2_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave2_t1, 0u, 0xffu);
+ ams_slave2_t2 = (uint8_t)src_p->ams_slave2_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave2_t2, 0u, 0xffu);
+ ams_slave2_t3 = (uint8_t)src_p->ams_slave2_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave2_t3, 0u, 0xffu);
+ ams_slave2_t4 = (uint8_t)src_p->ams_slave2_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave2_t4, 0u, 0xffu);
+ ams_slave2_t5 = (uint8_t)src_p->ams_slave2_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave2_t5, 0u, 0xffu);
+ ams_slave2_t6 = (uint8_t)src_p->ams_slave2_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave2_t6, 0u, 0xffu);
+ ams_slave2_t7 = (uint8_t)src_p->ams_slave2_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave2_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log5_unpack(
+ struct can1__main_ft24_ams_slave2_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t0;
+ uint8_t ams_slave2_t1;
+ uint8_t ams_slave2_t2;
+ uint8_t ams_slave2_t3;
+ uint8_t ams_slave2_t4;
+ uint8_t ams_slave2_t5;
+ uint8_t ams_slave2_t6;
+ uint8_t ams_slave2_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave2_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave2_t0 = (int8_t)ams_slave2_t0;
+ ams_slave2_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_t1 = (int8_t)ams_slave2_t1;
+ ams_slave2_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave2_t2 = (int8_t)ams_slave2_t2;
+ ams_slave2_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_t3 = (int8_t)ams_slave2_t3;
+ ams_slave2_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave2_t4 = (int8_t)ams_slave2_t4;
+ ams_slave2_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_t5 = (int8_t)ams_slave2_t5;
+ ams_slave2_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave2_t6 = (int8_t)ams_slave2_t6;
+ ams_slave2_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave2_t7 = (int8_t)ams_slave2_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log5_init(struct can1__main_ft24_ams_slave2_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log5_ams_slave2_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log5_ams_slave2_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log5_ams_slave2_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t10;
+ uint8_t ams_slave2_t11;
+ uint8_t ams_slave2_t12;
+ uint8_t ams_slave2_t13;
+ uint8_t ams_slave2_t14;
+ uint8_t ams_slave2_t15;
+ uint8_t ams_slave2_t8;
+ uint8_t ams_slave2_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave2_t8 = (uint8_t)src_p->ams_slave2_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave2_t8, 0u, 0xffu);
+ ams_slave2_t9 = (uint8_t)src_p->ams_slave2_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave2_t9, 0u, 0xffu);
+ ams_slave2_t10 = (uint8_t)src_p->ams_slave2_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave2_t10, 0u, 0xffu);
+ ams_slave2_t11 = (uint8_t)src_p->ams_slave2_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave2_t11, 0u, 0xffu);
+ ams_slave2_t12 = (uint8_t)src_p->ams_slave2_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave2_t12, 0u, 0xffu);
+ ams_slave2_t13 = (uint8_t)src_p->ams_slave2_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave2_t13, 0u, 0xffu);
+ ams_slave2_t14 = (uint8_t)src_p->ams_slave2_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave2_t14, 0u, 0xffu);
+ ams_slave2_t15 = (uint8_t)src_p->ams_slave2_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave2_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log6_unpack(
+ struct can1__main_ft24_ams_slave2_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t10;
+ uint8_t ams_slave2_t11;
+ uint8_t ams_slave2_t12;
+ uint8_t ams_slave2_t13;
+ uint8_t ams_slave2_t14;
+ uint8_t ams_slave2_t15;
+ uint8_t ams_slave2_t8;
+ uint8_t ams_slave2_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave2_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave2_t8 = (int8_t)ams_slave2_t8;
+ ams_slave2_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_t9 = (int8_t)ams_slave2_t9;
+ ams_slave2_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave2_t10 = (int8_t)ams_slave2_t10;
+ ams_slave2_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_t11 = (int8_t)ams_slave2_t11;
+ ams_slave2_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave2_t12 = (int8_t)ams_slave2_t12;
+ ams_slave2_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_t13 = (int8_t)ams_slave2_t13;
+ ams_slave2_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave2_t14 = (int8_t)ams_slave2_t14;
+ ams_slave2_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave2_t15 = (int8_t)ams_slave2_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log6_init(struct can1__main_ft24_ams_slave2_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log6_ams_slave2_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log6_ams_slave2_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log6_ams_slave2_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t16;
+ uint8_t ams_slave2_t17;
+ uint8_t ams_slave2_t18;
+ uint8_t ams_slave2_t19;
+ uint8_t ams_slave2_t20;
+ uint8_t ams_slave2_t21;
+ uint8_t ams_slave2_t22;
+ uint8_t ams_slave2_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave2_t16 = (uint8_t)src_p->ams_slave2_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave2_t16, 0u, 0xffu);
+ ams_slave2_t17 = (uint8_t)src_p->ams_slave2_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave2_t17, 0u, 0xffu);
+ ams_slave2_t18 = (uint8_t)src_p->ams_slave2_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave2_t18, 0u, 0xffu);
+ ams_slave2_t19 = (uint8_t)src_p->ams_slave2_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave2_t19, 0u, 0xffu);
+ ams_slave2_t20 = (uint8_t)src_p->ams_slave2_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave2_t20, 0u, 0xffu);
+ ams_slave2_t21 = (uint8_t)src_p->ams_slave2_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave2_t21, 0u, 0xffu);
+ ams_slave2_t22 = (uint8_t)src_p->ams_slave2_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave2_t22, 0u, 0xffu);
+ ams_slave2_t23 = (uint8_t)src_p->ams_slave2_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave2_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log7_unpack(
+ struct can1__main_ft24_ams_slave2_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t16;
+ uint8_t ams_slave2_t17;
+ uint8_t ams_slave2_t18;
+ uint8_t ams_slave2_t19;
+ uint8_t ams_slave2_t20;
+ uint8_t ams_slave2_t21;
+ uint8_t ams_slave2_t22;
+ uint8_t ams_slave2_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave2_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave2_t16 = (int8_t)ams_slave2_t16;
+ ams_slave2_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_t17 = (int8_t)ams_slave2_t17;
+ ams_slave2_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave2_t18 = (int8_t)ams_slave2_t18;
+ ams_slave2_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_t19 = (int8_t)ams_slave2_t19;
+ ams_slave2_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave2_t20 = (int8_t)ams_slave2_t20;
+ ams_slave2_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_t21 = (int8_t)ams_slave2_t21;
+ ams_slave2_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave2_t22 = (int8_t)ams_slave2_t22;
+ ams_slave2_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave2_t23 = (int8_t)ams_slave2_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log7_init(struct can1__main_ft24_ams_slave2_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log7_ams_slave2_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log7_ams_slave2_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log7_ams_slave2_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave2_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t24;
+ uint8_t ams_slave2_t25;
+ uint8_t ams_slave2_t26;
+ uint8_t ams_slave2_t27;
+ uint8_t ams_slave2_t28;
+ uint8_t ams_slave2_t29;
+ uint8_t ams_slave2_t30;
+ uint8_t ams_slave2_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave2_t24 = (uint8_t)src_p->ams_slave2_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave2_t24, 0u, 0xffu);
+ ams_slave2_t25 = (uint8_t)src_p->ams_slave2_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave2_t25, 0u, 0xffu);
+ ams_slave2_t26 = (uint8_t)src_p->ams_slave2_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave2_t26, 0u, 0xffu);
+ ams_slave2_t27 = (uint8_t)src_p->ams_slave2_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave2_t27, 0u, 0xffu);
+ ams_slave2_t28 = (uint8_t)src_p->ams_slave2_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave2_t28, 0u, 0xffu);
+ ams_slave2_t29 = (uint8_t)src_p->ams_slave2_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave2_t29, 0u, 0xffu);
+ ams_slave2_t30 = (uint8_t)src_p->ams_slave2_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave2_t30, 0u, 0xffu);
+ ams_slave2_t31 = (uint8_t)src_p->ams_slave2_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave2_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_log8_unpack(
+ struct can1__main_ft24_ams_slave2_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave2_t24;
+ uint8_t ams_slave2_t25;
+ uint8_t ams_slave2_t26;
+ uint8_t ams_slave2_t27;
+ uint8_t ams_slave2_t28;
+ uint8_t ams_slave2_t29;
+ uint8_t ams_slave2_t30;
+ uint8_t ams_slave2_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave2_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave2_t24 = (int8_t)ams_slave2_t24;
+ ams_slave2_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave2_t25 = (int8_t)ams_slave2_t25;
+ ams_slave2_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave2_t26 = (int8_t)ams_slave2_t26;
+ ams_slave2_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave2_t27 = (int8_t)ams_slave2_t27;
+ ams_slave2_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave2_t28 = (int8_t)ams_slave2_t28;
+ ams_slave2_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave2_t29 = (int8_t)ams_slave2_t29;
+ ams_slave2_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave2_t30 = (int8_t)ams_slave2_t30;
+ ams_slave2_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave2_t31 = (int8_t)ams_slave2_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_log8_init(struct can1__main_ft24_ams_slave2_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave2_log8_ams_slave2_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_log8_ams_slave2_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_log8_ams_slave2_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave3_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave3_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave3_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave3_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave3_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave3_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave3_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave3_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log0_unpack(
+ struct can1__main_ft24_ams_slave3_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave3_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave3_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave3_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave3_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave3_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log0_init(struct can1__main_ft24_ams_slave3_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log0_ams_slave3_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log0_ams_slave3_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log0_ams_slave3_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave3_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave3_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave3_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave3_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave3_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave3_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave3_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave3_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log1_unpack(
+ struct can1__main_ft24_ams_slave3_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave3_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave3_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave3_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave3_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave3_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log1_init(struct can1__main_ft24_ams_slave3_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log1_ams_slave3_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log1_ams_slave3_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log1_ams_slave3_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave3_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave3_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave3_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave3_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave3_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave3_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave3_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave3_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log2_unpack(
+ struct can1__main_ft24_ams_slave3_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave3_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave3_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave3_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave3_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave3_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log2_init(struct can1__main_ft24_ams_slave3_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log2_ams_slave3_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log2_ams_slave3_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log2_ams_slave3_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave3_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave3_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave3_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave3_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave3_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave3_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave3_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave3_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log3_unpack(
+ struct can1__main_ft24_ams_slave3_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave3_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave3_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave3_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave3_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave3_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log3_init(struct can1__main_ft24_ams_slave3_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave3_log3_ams_slave3_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log3_ams_slave3_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log3_ams_slave3_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave3_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave3_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave3_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave3_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave3_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave3_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave3_log4_unpack(
+ struct can1__main_ft24_ams_slave3_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave3_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave3_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave3_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave3_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave3_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log4_init(struct can1__main_ft24_ams_slave3_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave3_log4_ams_slave3_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_log4_ams_slave3_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_log4_ams_slave3_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave3_log4_ams_slave3_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log4_ams_slave3_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log4_ams_slave3_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t0;
+ uint8_t ams_slave3_t1;
+ uint8_t ams_slave3_t2;
+ uint8_t ams_slave3_t3;
+ uint8_t ams_slave3_t4;
+ uint8_t ams_slave3_t5;
+ uint8_t ams_slave3_t6;
+ uint8_t ams_slave3_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave3_t0 = (uint8_t)src_p->ams_slave3_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave3_t0, 0u, 0xffu);
+ ams_slave3_t1 = (uint8_t)src_p->ams_slave3_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave3_t1, 0u, 0xffu);
+ ams_slave3_t2 = (uint8_t)src_p->ams_slave3_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave3_t2, 0u, 0xffu);
+ ams_slave3_t3 = (uint8_t)src_p->ams_slave3_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave3_t3, 0u, 0xffu);
+ ams_slave3_t4 = (uint8_t)src_p->ams_slave3_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave3_t4, 0u, 0xffu);
+ ams_slave3_t5 = (uint8_t)src_p->ams_slave3_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave3_t5, 0u, 0xffu);
+ ams_slave3_t6 = (uint8_t)src_p->ams_slave3_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave3_t6, 0u, 0xffu);
+ ams_slave3_t7 = (uint8_t)src_p->ams_slave3_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave3_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log5_unpack(
+ struct can1__main_ft24_ams_slave3_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t0;
+ uint8_t ams_slave3_t1;
+ uint8_t ams_slave3_t2;
+ uint8_t ams_slave3_t3;
+ uint8_t ams_slave3_t4;
+ uint8_t ams_slave3_t5;
+ uint8_t ams_slave3_t6;
+ uint8_t ams_slave3_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave3_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave3_t0 = (int8_t)ams_slave3_t0;
+ ams_slave3_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_t1 = (int8_t)ams_slave3_t1;
+ ams_slave3_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave3_t2 = (int8_t)ams_slave3_t2;
+ ams_slave3_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_t3 = (int8_t)ams_slave3_t3;
+ ams_slave3_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave3_t4 = (int8_t)ams_slave3_t4;
+ ams_slave3_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_t5 = (int8_t)ams_slave3_t5;
+ ams_slave3_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave3_t6 = (int8_t)ams_slave3_t6;
+ ams_slave3_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave3_t7 = (int8_t)ams_slave3_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log5_init(struct can1__main_ft24_ams_slave3_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log5_ams_slave3_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log5_ams_slave3_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log5_ams_slave3_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t10;
+ uint8_t ams_slave3_t11;
+ uint8_t ams_slave3_t12;
+ uint8_t ams_slave3_t13;
+ uint8_t ams_slave3_t14;
+ uint8_t ams_slave3_t15;
+ uint8_t ams_slave3_t8;
+ uint8_t ams_slave3_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave3_t8 = (uint8_t)src_p->ams_slave3_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave3_t8, 0u, 0xffu);
+ ams_slave3_t9 = (uint8_t)src_p->ams_slave3_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave3_t9, 0u, 0xffu);
+ ams_slave3_t10 = (uint8_t)src_p->ams_slave3_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave3_t10, 0u, 0xffu);
+ ams_slave3_t11 = (uint8_t)src_p->ams_slave3_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave3_t11, 0u, 0xffu);
+ ams_slave3_t12 = (uint8_t)src_p->ams_slave3_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave3_t12, 0u, 0xffu);
+ ams_slave3_t13 = (uint8_t)src_p->ams_slave3_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave3_t13, 0u, 0xffu);
+ ams_slave3_t14 = (uint8_t)src_p->ams_slave3_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave3_t14, 0u, 0xffu);
+ ams_slave3_t15 = (uint8_t)src_p->ams_slave3_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave3_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log6_unpack(
+ struct can1__main_ft24_ams_slave3_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t10;
+ uint8_t ams_slave3_t11;
+ uint8_t ams_slave3_t12;
+ uint8_t ams_slave3_t13;
+ uint8_t ams_slave3_t14;
+ uint8_t ams_slave3_t15;
+ uint8_t ams_slave3_t8;
+ uint8_t ams_slave3_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave3_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave3_t8 = (int8_t)ams_slave3_t8;
+ ams_slave3_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_t9 = (int8_t)ams_slave3_t9;
+ ams_slave3_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave3_t10 = (int8_t)ams_slave3_t10;
+ ams_slave3_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_t11 = (int8_t)ams_slave3_t11;
+ ams_slave3_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave3_t12 = (int8_t)ams_slave3_t12;
+ ams_slave3_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_t13 = (int8_t)ams_slave3_t13;
+ ams_slave3_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave3_t14 = (int8_t)ams_slave3_t14;
+ ams_slave3_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave3_t15 = (int8_t)ams_slave3_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log6_init(struct can1__main_ft24_ams_slave3_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log6_ams_slave3_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log6_ams_slave3_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log6_ams_slave3_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t16;
+ uint8_t ams_slave3_t17;
+ uint8_t ams_slave3_t18;
+ uint8_t ams_slave3_t19;
+ uint8_t ams_slave3_t20;
+ uint8_t ams_slave3_t21;
+ uint8_t ams_slave3_t22;
+ uint8_t ams_slave3_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave3_t16 = (uint8_t)src_p->ams_slave3_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave3_t16, 0u, 0xffu);
+ ams_slave3_t17 = (uint8_t)src_p->ams_slave3_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave3_t17, 0u, 0xffu);
+ ams_slave3_t18 = (uint8_t)src_p->ams_slave3_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave3_t18, 0u, 0xffu);
+ ams_slave3_t19 = (uint8_t)src_p->ams_slave3_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave3_t19, 0u, 0xffu);
+ ams_slave3_t20 = (uint8_t)src_p->ams_slave3_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave3_t20, 0u, 0xffu);
+ ams_slave3_t21 = (uint8_t)src_p->ams_slave3_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave3_t21, 0u, 0xffu);
+ ams_slave3_t22 = (uint8_t)src_p->ams_slave3_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave3_t22, 0u, 0xffu);
+ ams_slave3_t23 = (uint8_t)src_p->ams_slave3_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave3_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log7_unpack(
+ struct can1__main_ft24_ams_slave3_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t16;
+ uint8_t ams_slave3_t17;
+ uint8_t ams_slave3_t18;
+ uint8_t ams_slave3_t19;
+ uint8_t ams_slave3_t20;
+ uint8_t ams_slave3_t21;
+ uint8_t ams_slave3_t22;
+ uint8_t ams_slave3_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave3_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave3_t16 = (int8_t)ams_slave3_t16;
+ ams_slave3_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_t17 = (int8_t)ams_slave3_t17;
+ ams_slave3_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave3_t18 = (int8_t)ams_slave3_t18;
+ ams_slave3_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_t19 = (int8_t)ams_slave3_t19;
+ ams_slave3_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave3_t20 = (int8_t)ams_slave3_t20;
+ ams_slave3_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_t21 = (int8_t)ams_slave3_t21;
+ ams_slave3_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave3_t22 = (int8_t)ams_slave3_t22;
+ ams_slave3_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave3_t23 = (int8_t)ams_slave3_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log7_init(struct can1__main_ft24_ams_slave3_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log7_ams_slave3_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log7_ams_slave3_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log7_ams_slave3_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave3_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t24;
+ uint8_t ams_slave3_t25;
+ uint8_t ams_slave3_t26;
+ uint8_t ams_slave3_t27;
+ uint8_t ams_slave3_t28;
+ uint8_t ams_slave3_t29;
+ uint8_t ams_slave3_t30;
+ uint8_t ams_slave3_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave3_t24 = (uint8_t)src_p->ams_slave3_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave3_t24, 0u, 0xffu);
+ ams_slave3_t25 = (uint8_t)src_p->ams_slave3_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave3_t25, 0u, 0xffu);
+ ams_slave3_t26 = (uint8_t)src_p->ams_slave3_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave3_t26, 0u, 0xffu);
+ ams_slave3_t27 = (uint8_t)src_p->ams_slave3_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave3_t27, 0u, 0xffu);
+ ams_slave3_t28 = (uint8_t)src_p->ams_slave3_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave3_t28, 0u, 0xffu);
+ ams_slave3_t29 = (uint8_t)src_p->ams_slave3_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave3_t29, 0u, 0xffu);
+ ams_slave3_t30 = (uint8_t)src_p->ams_slave3_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave3_t30, 0u, 0xffu);
+ ams_slave3_t31 = (uint8_t)src_p->ams_slave3_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave3_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_log8_unpack(
+ struct can1__main_ft24_ams_slave3_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave3_t24;
+ uint8_t ams_slave3_t25;
+ uint8_t ams_slave3_t26;
+ uint8_t ams_slave3_t27;
+ uint8_t ams_slave3_t28;
+ uint8_t ams_slave3_t29;
+ uint8_t ams_slave3_t30;
+ uint8_t ams_slave3_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave3_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave3_t24 = (int8_t)ams_slave3_t24;
+ ams_slave3_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave3_t25 = (int8_t)ams_slave3_t25;
+ ams_slave3_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave3_t26 = (int8_t)ams_slave3_t26;
+ ams_slave3_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave3_t27 = (int8_t)ams_slave3_t27;
+ ams_slave3_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave3_t28 = (int8_t)ams_slave3_t28;
+ ams_slave3_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave3_t29 = (int8_t)ams_slave3_t29;
+ ams_slave3_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave3_t30 = (int8_t)ams_slave3_t30;
+ ams_slave3_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave3_t31 = (int8_t)ams_slave3_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_log8_init(struct can1__main_ft24_ams_slave3_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave3_log8_ams_slave3_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_log8_ams_slave3_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_log8_ams_slave3_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave4_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave4_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave4_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave4_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave4_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave4_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave4_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave4_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log0_unpack(
+ struct can1__main_ft24_ams_slave4_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave4_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave4_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave4_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave4_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave4_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log0_init(struct can1__main_ft24_ams_slave4_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log0_ams_slave4_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log0_ams_slave4_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log0_ams_slave4_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave4_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave4_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave4_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave4_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave4_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave4_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave4_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave4_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log1_unpack(
+ struct can1__main_ft24_ams_slave4_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave4_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave4_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave4_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave4_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave4_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log1_init(struct can1__main_ft24_ams_slave4_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log1_ams_slave4_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log1_ams_slave4_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log1_ams_slave4_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave4_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave4_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave4_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave4_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave4_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave4_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave4_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave4_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log2_unpack(
+ struct can1__main_ft24_ams_slave4_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave4_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave4_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave4_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave4_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave4_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log2_init(struct can1__main_ft24_ams_slave4_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log2_ams_slave4_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log2_ams_slave4_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log2_ams_slave4_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave4_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave4_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave4_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave4_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave4_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave4_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave4_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave4_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log3_unpack(
+ struct can1__main_ft24_ams_slave4_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave4_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave4_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave4_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave4_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave4_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log3_init(struct can1__main_ft24_ams_slave4_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave4_log3_ams_slave4_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log3_ams_slave4_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log3_ams_slave4_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave4_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave4_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave4_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave4_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave4_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave4_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave4_log4_unpack(
+ struct can1__main_ft24_ams_slave4_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave4_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave4_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave4_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave4_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave4_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log4_init(struct can1__main_ft24_ams_slave4_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave4_log4_ams_slave4_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_log4_ams_slave4_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_log4_ams_slave4_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave4_log4_ams_slave4_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log4_ams_slave4_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log4_ams_slave4_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t0;
+ uint8_t ams_slave4_t1;
+ uint8_t ams_slave4_t2;
+ uint8_t ams_slave4_t3;
+ uint8_t ams_slave4_t4;
+ uint8_t ams_slave4_t5;
+ uint8_t ams_slave4_t6;
+ uint8_t ams_slave4_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave4_t0 = (uint8_t)src_p->ams_slave4_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave4_t0, 0u, 0xffu);
+ ams_slave4_t1 = (uint8_t)src_p->ams_slave4_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave4_t1, 0u, 0xffu);
+ ams_slave4_t2 = (uint8_t)src_p->ams_slave4_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave4_t2, 0u, 0xffu);
+ ams_slave4_t3 = (uint8_t)src_p->ams_slave4_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave4_t3, 0u, 0xffu);
+ ams_slave4_t4 = (uint8_t)src_p->ams_slave4_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave4_t4, 0u, 0xffu);
+ ams_slave4_t5 = (uint8_t)src_p->ams_slave4_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave4_t5, 0u, 0xffu);
+ ams_slave4_t6 = (uint8_t)src_p->ams_slave4_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave4_t6, 0u, 0xffu);
+ ams_slave4_t7 = (uint8_t)src_p->ams_slave4_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave4_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log5_unpack(
+ struct can1__main_ft24_ams_slave4_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t0;
+ uint8_t ams_slave4_t1;
+ uint8_t ams_slave4_t2;
+ uint8_t ams_slave4_t3;
+ uint8_t ams_slave4_t4;
+ uint8_t ams_slave4_t5;
+ uint8_t ams_slave4_t6;
+ uint8_t ams_slave4_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave4_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave4_t0 = (int8_t)ams_slave4_t0;
+ ams_slave4_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_t1 = (int8_t)ams_slave4_t1;
+ ams_slave4_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave4_t2 = (int8_t)ams_slave4_t2;
+ ams_slave4_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_t3 = (int8_t)ams_slave4_t3;
+ ams_slave4_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave4_t4 = (int8_t)ams_slave4_t4;
+ ams_slave4_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_t5 = (int8_t)ams_slave4_t5;
+ ams_slave4_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave4_t6 = (int8_t)ams_slave4_t6;
+ ams_slave4_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave4_t7 = (int8_t)ams_slave4_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log5_init(struct can1__main_ft24_ams_slave4_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log5_ams_slave4_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log5_ams_slave4_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log5_ams_slave4_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t10;
+ uint8_t ams_slave4_t11;
+ uint8_t ams_slave4_t12;
+ uint8_t ams_slave4_t13;
+ uint8_t ams_slave4_t14;
+ uint8_t ams_slave4_t15;
+ uint8_t ams_slave4_t8;
+ uint8_t ams_slave4_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave4_t8 = (uint8_t)src_p->ams_slave4_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave4_t8, 0u, 0xffu);
+ ams_slave4_t9 = (uint8_t)src_p->ams_slave4_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave4_t9, 0u, 0xffu);
+ ams_slave4_t10 = (uint8_t)src_p->ams_slave4_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave4_t10, 0u, 0xffu);
+ ams_slave4_t11 = (uint8_t)src_p->ams_slave4_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave4_t11, 0u, 0xffu);
+ ams_slave4_t12 = (uint8_t)src_p->ams_slave4_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave4_t12, 0u, 0xffu);
+ ams_slave4_t13 = (uint8_t)src_p->ams_slave4_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave4_t13, 0u, 0xffu);
+ ams_slave4_t14 = (uint8_t)src_p->ams_slave4_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave4_t14, 0u, 0xffu);
+ ams_slave4_t15 = (uint8_t)src_p->ams_slave4_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave4_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log6_unpack(
+ struct can1__main_ft24_ams_slave4_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t10;
+ uint8_t ams_slave4_t11;
+ uint8_t ams_slave4_t12;
+ uint8_t ams_slave4_t13;
+ uint8_t ams_slave4_t14;
+ uint8_t ams_slave4_t15;
+ uint8_t ams_slave4_t8;
+ uint8_t ams_slave4_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave4_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave4_t8 = (int8_t)ams_slave4_t8;
+ ams_slave4_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_t9 = (int8_t)ams_slave4_t9;
+ ams_slave4_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave4_t10 = (int8_t)ams_slave4_t10;
+ ams_slave4_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_t11 = (int8_t)ams_slave4_t11;
+ ams_slave4_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave4_t12 = (int8_t)ams_slave4_t12;
+ ams_slave4_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_t13 = (int8_t)ams_slave4_t13;
+ ams_slave4_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave4_t14 = (int8_t)ams_slave4_t14;
+ ams_slave4_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave4_t15 = (int8_t)ams_slave4_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log6_init(struct can1__main_ft24_ams_slave4_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log6_ams_slave4_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log6_ams_slave4_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log6_ams_slave4_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t16;
+ uint8_t ams_slave4_t17;
+ uint8_t ams_slave4_t18;
+ uint8_t ams_slave4_t19;
+ uint8_t ams_slave4_t20;
+ uint8_t ams_slave4_t21;
+ uint8_t ams_slave4_t22;
+ uint8_t ams_slave4_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave4_t16 = (uint8_t)src_p->ams_slave4_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave4_t16, 0u, 0xffu);
+ ams_slave4_t17 = (uint8_t)src_p->ams_slave4_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave4_t17, 0u, 0xffu);
+ ams_slave4_t18 = (uint8_t)src_p->ams_slave4_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave4_t18, 0u, 0xffu);
+ ams_slave4_t19 = (uint8_t)src_p->ams_slave4_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave4_t19, 0u, 0xffu);
+ ams_slave4_t20 = (uint8_t)src_p->ams_slave4_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave4_t20, 0u, 0xffu);
+ ams_slave4_t21 = (uint8_t)src_p->ams_slave4_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave4_t21, 0u, 0xffu);
+ ams_slave4_t22 = (uint8_t)src_p->ams_slave4_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave4_t22, 0u, 0xffu);
+ ams_slave4_t23 = (uint8_t)src_p->ams_slave4_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave4_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log7_unpack(
+ struct can1__main_ft24_ams_slave4_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t16;
+ uint8_t ams_slave4_t17;
+ uint8_t ams_slave4_t18;
+ uint8_t ams_slave4_t19;
+ uint8_t ams_slave4_t20;
+ uint8_t ams_slave4_t21;
+ uint8_t ams_slave4_t22;
+ uint8_t ams_slave4_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave4_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave4_t16 = (int8_t)ams_slave4_t16;
+ ams_slave4_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_t17 = (int8_t)ams_slave4_t17;
+ ams_slave4_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave4_t18 = (int8_t)ams_slave4_t18;
+ ams_slave4_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_t19 = (int8_t)ams_slave4_t19;
+ ams_slave4_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave4_t20 = (int8_t)ams_slave4_t20;
+ ams_slave4_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_t21 = (int8_t)ams_slave4_t21;
+ ams_slave4_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave4_t22 = (int8_t)ams_slave4_t22;
+ ams_slave4_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave4_t23 = (int8_t)ams_slave4_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log7_init(struct can1__main_ft24_ams_slave4_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log7_ams_slave4_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log7_ams_slave4_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log7_ams_slave4_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave4_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t24;
+ uint8_t ams_slave4_t25;
+ uint8_t ams_slave4_t26;
+ uint8_t ams_slave4_t27;
+ uint8_t ams_slave4_t28;
+ uint8_t ams_slave4_t29;
+ uint8_t ams_slave4_t30;
+ uint8_t ams_slave4_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave4_t24 = (uint8_t)src_p->ams_slave4_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave4_t24, 0u, 0xffu);
+ ams_slave4_t25 = (uint8_t)src_p->ams_slave4_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave4_t25, 0u, 0xffu);
+ ams_slave4_t26 = (uint8_t)src_p->ams_slave4_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave4_t26, 0u, 0xffu);
+ ams_slave4_t27 = (uint8_t)src_p->ams_slave4_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave4_t27, 0u, 0xffu);
+ ams_slave4_t28 = (uint8_t)src_p->ams_slave4_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave4_t28, 0u, 0xffu);
+ ams_slave4_t29 = (uint8_t)src_p->ams_slave4_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave4_t29, 0u, 0xffu);
+ ams_slave4_t30 = (uint8_t)src_p->ams_slave4_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave4_t30, 0u, 0xffu);
+ ams_slave4_t31 = (uint8_t)src_p->ams_slave4_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave4_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_log8_unpack(
+ struct can1__main_ft24_ams_slave4_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave4_t24;
+ uint8_t ams_slave4_t25;
+ uint8_t ams_slave4_t26;
+ uint8_t ams_slave4_t27;
+ uint8_t ams_slave4_t28;
+ uint8_t ams_slave4_t29;
+ uint8_t ams_slave4_t30;
+ uint8_t ams_slave4_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave4_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave4_t24 = (int8_t)ams_slave4_t24;
+ ams_slave4_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave4_t25 = (int8_t)ams_slave4_t25;
+ ams_slave4_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave4_t26 = (int8_t)ams_slave4_t26;
+ ams_slave4_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave4_t27 = (int8_t)ams_slave4_t27;
+ ams_slave4_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave4_t28 = (int8_t)ams_slave4_t28;
+ ams_slave4_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave4_t29 = (int8_t)ams_slave4_t29;
+ ams_slave4_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave4_t30 = (int8_t)ams_slave4_t30;
+ ams_slave4_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave4_t31 = (int8_t)ams_slave4_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_log8_init(struct can1__main_ft24_ams_slave4_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave4_log8_ams_slave4_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_log8_ams_slave4_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_log8_ams_slave4_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave5_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave5_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave5_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave5_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave5_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave5_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave5_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave5_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log0_unpack(
+ struct can1__main_ft24_ams_slave5_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave5_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave5_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave5_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave5_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave5_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log0_init(struct can1__main_ft24_ams_slave5_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log0_ams_slave5_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log0_ams_slave5_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log0_ams_slave5_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave5_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave5_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave5_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave5_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave5_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave5_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave5_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave5_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log1_unpack(
+ struct can1__main_ft24_ams_slave5_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave5_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave5_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave5_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave5_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave5_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log1_init(struct can1__main_ft24_ams_slave5_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log1_ams_slave5_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log1_ams_slave5_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log1_ams_slave5_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave5_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave5_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave5_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave5_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave5_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave5_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave5_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave5_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log2_unpack(
+ struct can1__main_ft24_ams_slave5_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave5_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave5_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave5_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave5_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave5_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log2_init(struct can1__main_ft24_ams_slave5_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log2_ams_slave5_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log2_ams_slave5_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log2_ams_slave5_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave5_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave5_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave5_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave5_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave5_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave5_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave5_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave5_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log3_unpack(
+ struct can1__main_ft24_ams_slave5_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave5_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave5_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave5_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave5_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave5_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log3_init(struct can1__main_ft24_ams_slave5_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave5_log3_ams_slave5_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log3_ams_slave5_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log3_ams_slave5_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave5_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave5_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave5_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave5_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave5_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave5_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave5_log4_unpack(
+ struct can1__main_ft24_ams_slave5_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave5_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave5_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave5_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave5_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave5_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log4_init(struct can1__main_ft24_ams_slave5_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave5_log4_ams_slave5_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_log4_ams_slave5_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_log4_ams_slave5_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave5_log4_ams_slave5_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log4_ams_slave5_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log4_ams_slave5_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t0;
+ uint8_t ams_slave5_t1;
+ uint8_t ams_slave5_t2;
+ uint8_t ams_slave5_t3;
+ uint8_t ams_slave5_t4;
+ uint8_t ams_slave5_t5;
+ uint8_t ams_slave5_t6;
+ uint8_t ams_slave5_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave5_t0 = (uint8_t)src_p->ams_slave5_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave5_t0, 0u, 0xffu);
+ ams_slave5_t1 = (uint8_t)src_p->ams_slave5_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave5_t1, 0u, 0xffu);
+ ams_slave5_t2 = (uint8_t)src_p->ams_slave5_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave5_t2, 0u, 0xffu);
+ ams_slave5_t3 = (uint8_t)src_p->ams_slave5_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave5_t3, 0u, 0xffu);
+ ams_slave5_t4 = (uint8_t)src_p->ams_slave5_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave5_t4, 0u, 0xffu);
+ ams_slave5_t5 = (uint8_t)src_p->ams_slave5_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave5_t5, 0u, 0xffu);
+ ams_slave5_t6 = (uint8_t)src_p->ams_slave5_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave5_t6, 0u, 0xffu);
+ ams_slave5_t7 = (uint8_t)src_p->ams_slave5_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave5_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log5_unpack(
+ struct can1__main_ft24_ams_slave5_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t0;
+ uint8_t ams_slave5_t1;
+ uint8_t ams_slave5_t2;
+ uint8_t ams_slave5_t3;
+ uint8_t ams_slave5_t4;
+ uint8_t ams_slave5_t5;
+ uint8_t ams_slave5_t6;
+ uint8_t ams_slave5_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave5_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave5_t0 = (int8_t)ams_slave5_t0;
+ ams_slave5_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_t1 = (int8_t)ams_slave5_t1;
+ ams_slave5_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave5_t2 = (int8_t)ams_slave5_t2;
+ ams_slave5_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_t3 = (int8_t)ams_slave5_t3;
+ ams_slave5_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave5_t4 = (int8_t)ams_slave5_t4;
+ ams_slave5_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_t5 = (int8_t)ams_slave5_t5;
+ ams_slave5_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave5_t6 = (int8_t)ams_slave5_t6;
+ ams_slave5_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave5_t7 = (int8_t)ams_slave5_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log5_init(struct can1__main_ft24_ams_slave5_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log5_ams_slave5_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log5_ams_slave5_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log5_ams_slave5_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t10;
+ uint8_t ams_slave5_t11;
+ uint8_t ams_slave5_t12;
+ uint8_t ams_slave5_t13;
+ uint8_t ams_slave5_t14;
+ uint8_t ams_slave5_t15;
+ uint8_t ams_slave5_t8;
+ uint8_t ams_slave5_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave5_t8 = (uint8_t)src_p->ams_slave5_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave5_t8, 0u, 0xffu);
+ ams_slave5_t9 = (uint8_t)src_p->ams_slave5_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave5_t9, 0u, 0xffu);
+ ams_slave5_t10 = (uint8_t)src_p->ams_slave5_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave5_t10, 0u, 0xffu);
+ ams_slave5_t11 = (uint8_t)src_p->ams_slave5_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave5_t11, 0u, 0xffu);
+ ams_slave5_t12 = (uint8_t)src_p->ams_slave5_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave5_t12, 0u, 0xffu);
+ ams_slave5_t13 = (uint8_t)src_p->ams_slave5_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave5_t13, 0u, 0xffu);
+ ams_slave5_t14 = (uint8_t)src_p->ams_slave5_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave5_t14, 0u, 0xffu);
+ ams_slave5_t15 = (uint8_t)src_p->ams_slave5_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave5_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log6_unpack(
+ struct can1__main_ft24_ams_slave5_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t10;
+ uint8_t ams_slave5_t11;
+ uint8_t ams_slave5_t12;
+ uint8_t ams_slave5_t13;
+ uint8_t ams_slave5_t14;
+ uint8_t ams_slave5_t15;
+ uint8_t ams_slave5_t8;
+ uint8_t ams_slave5_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave5_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave5_t8 = (int8_t)ams_slave5_t8;
+ ams_slave5_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_t9 = (int8_t)ams_slave5_t9;
+ ams_slave5_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave5_t10 = (int8_t)ams_slave5_t10;
+ ams_slave5_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_t11 = (int8_t)ams_slave5_t11;
+ ams_slave5_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave5_t12 = (int8_t)ams_slave5_t12;
+ ams_slave5_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_t13 = (int8_t)ams_slave5_t13;
+ ams_slave5_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave5_t14 = (int8_t)ams_slave5_t14;
+ ams_slave5_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave5_t15 = (int8_t)ams_slave5_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log6_init(struct can1__main_ft24_ams_slave5_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log6_ams_slave5_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log6_ams_slave5_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log6_ams_slave5_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t16;
+ uint8_t ams_slave5_t17;
+ uint8_t ams_slave5_t18;
+ uint8_t ams_slave5_t19;
+ uint8_t ams_slave5_t20;
+ uint8_t ams_slave5_t21;
+ uint8_t ams_slave5_t22;
+ uint8_t ams_slave5_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave5_t16 = (uint8_t)src_p->ams_slave5_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave5_t16, 0u, 0xffu);
+ ams_slave5_t17 = (uint8_t)src_p->ams_slave5_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave5_t17, 0u, 0xffu);
+ ams_slave5_t18 = (uint8_t)src_p->ams_slave5_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave5_t18, 0u, 0xffu);
+ ams_slave5_t19 = (uint8_t)src_p->ams_slave5_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave5_t19, 0u, 0xffu);
+ ams_slave5_t20 = (uint8_t)src_p->ams_slave5_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave5_t20, 0u, 0xffu);
+ ams_slave5_t21 = (uint8_t)src_p->ams_slave5_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave5_t21, 0u, 0xffu);
+ ams_slave5_t22 = (uint8_t)src_p->ams_slave5_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave5_t22, 0u, 0xffu);
+ ams_slave5_t23 = (uint8_t)src_p->ams_slave5_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave5_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log7_unpack(
+ struct can1__main_ft24_ams_slave5_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t16;
+ uint8_t ams_slave5_t17;
+ uint8_t ams_slave5_t18;
+ uint8_t ams_slave5_t19;
+ uint8_t ams_slave5_t20;
+ uint8_t ams_slave5_t21;
+ uint8_t ams_slave5_t22;
+ uint8_t ams_slave5_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave5_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave5_t16 = (int8_t)ams_slave5_t16;
+ ams_slave5_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_t17 = (int8_t)ams_slave5_t17;
+ ams_slave5_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave5_t18 = (int8_t)ams_slave5_t18;
+ ams_slave5_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_t19 = (int8_t)ams_slave5_t19;
+ ams_slave5_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave5_t20 = (int8_t)ams_slave5_t20;
+ ams_slave5_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_t21 = (int8_t)ams_slave5_t21;
+ ams_slave5_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave5_t22 = (int8_t)ams_slave5_t22;
+ ams_slave5_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave5_t23 = (int8_t)ams_slave5_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log7_init(struct can1__main_ft24_ams_slave5_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log7_ams_slave5_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log7_ams_slave5_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log7_ams_slave5_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave5_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t24;
+ uint8_t ams_slave5_t25;
+ uint8_t ams_slave5_t26;
+ uint8_t ams_slave5_t27;
+ uint8_t ams_slave5_t28;
+ uint8_t ams_slave5_t29;
+ uint8_t ams_slave5_t30;
+ uint8_t ams_slave5_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave5_t24 = (uint8_t)src_p->ams_slave5_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave5_t24, 0u, 0xffu);
+ ams_slave5_t25 = (uint8_t)src_p->ams_slave5_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave5_t25, 0u, 0xffu);
+ ams_slave5_t26 = (uint8_t)src_p->ams_slave5_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave5_t26, 0u, 0xffu);
+ ams_slave5_t27 = (uint8_t)src_p->ams_slave5_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave5_t27, 0u, 0xffu);
+ ams_slave5_t28 = (uint8_t)src_p->ams_slave5_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave5_t28, 0u, 0xffu);
+ ams_slave5_t29 = (uint8_t)src_p->ams_slave5_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave5_t29, 0u, 0xffu);
+ ams_slave5_t30 = (uint8_t)src_p->ams_slave5_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave5_t30, 0u, 0xffu);
+ ams_slave5_t31 = (uint8_t)src_p->ams_slave5_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave5_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_log8_unpack(
+ struct can1__main_ft24_ams_slave5_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave5_t24;
+ uint8_t ams_slave5_t25;
+ uint8_t ams_slave5_t26;
+ uint8_t ams_slave5_t27;
+ uint8_t ams_slave5_t28;
+ uint8_t ams_slave5_t29;
+ uint8_t ams_slave5_t30;
+ uint8_t ams_slave5_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave5_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave5_t24 = (int8_t)ams_slave5_t24;
+ ams_slave5_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave5_t25 = (int8_t)ams_slave5_t25;
+ ams_slave5_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave5_t26 = (int8_t)ams_slave5_t26;
+ ams_slave5_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave5_t27 = (int8_t)ams_slave5_t27;
+ ams_slave5_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave5_t28 = (int8_t)ams_slave5_t28;
+ ams_slave5_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave5_t29 = (int8_t)ams_slave5_t29;
+ ams_slave5_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave5_t30 = (int8_t)ams_slave5_t30;
+ ams_slave5_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave5_t31 = (int8_t)ams_slave5_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_log8_init(struct can1__main_ft24_ams_slave5_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave5_log8_ams_slave5_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_log8_ams_slave5_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_log8_ams_slave5_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave6_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave6_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave6_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave6_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave6_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave6_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave6_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave6_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log0_unpack(
+ struct can1__main_ft24_ams_slave6_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave6_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave6_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave6_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave6_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave6_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log0_init(struct can1__main_ft24_ams_slave6_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log0_ams_slave6_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log0_ams_slave6_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log0_ams_slave6_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave6_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave6_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave6_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave6_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave6_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave6_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave6_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave6_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log1_unpack(
+ struct can1__main_ft24_ams_slave6_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave6_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave6_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave6_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave6_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave6_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log1_init(struct can1__main_ft24_ams_slave6_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log1_ams_slave6_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log1_ams_slave6_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log1_ams_slave6_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave6_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave6_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave6_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave6_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave6_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave6_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave6_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave6_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log2_unpack(
+ struct can1__main_ft24_ams_slave6_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave6_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave6_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave6_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave6_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave6_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log2_init(struct can1__main_ft24_ams_slave6_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log2_ams_slave6_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log2_ams_slave6_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log2_ams_slave6_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave6_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave6_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave6_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave6_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave6_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave6_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave6_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave6_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log3_unpack(
+ struct can1__main_ft24_ams_slave6_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave6_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave6_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave6_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave6_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave6_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log3_init(struct can1__main_ft24_ams_slave6_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave6_log3_ams_slave6_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log3_ams_slave6_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log3_ams_slave6_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave6_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave6_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave6_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave6_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave6_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave6_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave6_log4_unpack(
+ struct can1__main_ft24_ams_slave6_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave6_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave6_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave6_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave6_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave6_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log4_init(struct can1__main_ft24_ams_slave6_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave6_log4_ams_slave6_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_log4_ams_slave6_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_log4_ams_slave6_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave6_log4_ams_slave6_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log4_ams_slave6_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log4_ams_slave6_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t0;
+ uint8_t ams_slave6_t1;
+ uint8_t ams_slave6_t2;
+ uint8_t ams_slave6_t3;
+ uint8_t ams_slave6_t4;
+ uint8_t ams_slave6_t5;
+ uint8_t ams_slave6_t6;
+ uint8_t ams_slave6_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave6_t0 = (uint8_t)src_p->ams_slave6_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave6_t0, 0u, 0xffu);
+ ams_slave6_t1 = (uint8_t)src_p->ams_slave6_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave6_t1, 0u, 0xffu);
+ ams_slave6_t2 = (uint8_t)src_p->ams_slave6_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave6_t2, 0u, 0xffu);
+ ams_slave6_t3 = (uint8_t)src_p->ams_slave6_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave6_t3, 0u, 0xffu);
+ ams_slave6_t4 = (uint8_t)src_p->ams_slave6_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave6_t4, 0u, 0xffu);
+ ams_slave6_t5 = (uint8_t)src_p->ams_slave6_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave6_t5, 0u, 0xffu);
+ ams_slave6_t6 = (uint8_t)src_p->ams_slave6_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave6_t6, 0u, 0xffu);
+ ams_slave6_t7 = (uint8_t)src_p->ams_slave6_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave6_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log5_unpack(
+ struct can1__main_ft24_ams_slave6_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t0;
+ uint8_t ams_slave6_t1;
+ uint8_t ams_slave6_t2;
+ uint8_t ams_slave6_t3;
+ uint8_t ams_slave6_t4;
+ uint8_t ams_slave6_t5;
+ uint8_t ams_slave6_t6;
+ uint8_t ams_slave6_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave6_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave6_t0 = (int8_t)ams_slave6_t0;
+ ams_slave6_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_t1 = (int8_t)ams_slave6_t1;
+ ams_slave6_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave6_t2 = (int8_t)ams_slave6_t2;
+ ams_slave6_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_t3 = (int8_t)ams_slave6_t3;
+ ams_slave6_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave6_t4 = (int8_t)ams_slave6_t4;
+ ams_slave6_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_t5 = (int8_t)ams_slave6_t5;
+ ams_slave6_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave6_t6 = (int8_t)ams_slave6_t6;
+ ams_slave6_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave6_t7 = (int8_t)ams_slave6_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log5_init(struct can1__main_ft24_ams_slave6_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log5_ams_slave6_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log5_ams_slave6_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log5_ams_slave6_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t10;
+ uint8_t ams_slave6_t11;
+ uint8_t ams_slave6_t12;
+ uint8_t ams_slave6_t13;
+ uint8_t ams_slave6_t14;
+ uint8_t ams_slave6_t15;
+ uint8_t ams_slave6_t8;
+ uint8_t ams_slave6_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave6_t8 = (uint8_t)src_p->ams_slave6_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave6_t8, 0u, 0xffu);
+ ams_slave6_t9 = (uint8_t)src_p->ams_slave6_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave6_t9, 0u, 0xffu);
+ ams_slave6_t10 = (uint8_t)src_p->ams_slave6_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave6_t10, 0u, 0xffu);
+ ams_slave6_t11 = (uint8_t)src_p->ams_slave6_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave6_t11, 0u, 0xffu);
+ ams_slave6_t12 = (uint8_t)src_p->ams_slave6_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave6_t12, 0u, 0xffu);
+ ams_slave6_t13 = (uint8_t)src_p->ams_slave6_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave6_t13, 0u, 0xffu);
+ ams_slave6_t14 = (uint8_t)src_p->ams_slave6_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave6_t14, 0u, 0xffu);
+ ams_slave6_t15 = (uint8_t)src_p->ams_slave6_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave6_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log6_unpack(
+ struct can1__main_ft24_ams_slave6_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t10;
+ uint8_t ams_slave6_t11;
+ uint8_t ams_slave6_t12;
+ uint8_t ams_slave6_t13;
+ uint8_t ams_slave6_t14;
+ uint8_t ams_slave6_t15;
+ uint8_t ams_slave6_t8;
+ uint8_t ams_slave6_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave6_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave6_t8 = (int8_t)ams_slave6_t8;
+ ams_slave6_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_t9 = (int8_t)ams_slave6_t9;
+ ams_slave6_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave6_t10 = (int8_t)ams_slave6_t10;
+ ams_slave6_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_t11 = (int8_t)ams_slave6_t11;
+ ams_slave6_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave6_t12 = (int8_t)ams_slave6_t12;
+ ams_slave6_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_t13 = (int8_t)ams_slave6_t13;
+ ams_slave6_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave6_t14 = (int8_t)ams_slave6_t14;
+ ams_slave6_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave6_t15 = (int8_t)ams_slave6_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log6_init(struct can1__main_ft24_ams_slave6_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log6_ams_slave6_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log6_ams_slave6_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log6_ams_slave6_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t16;
+ uint8_t ams_slave6_t17;
+ uint8_t ams_slave6_t18;
+ uint8_t ams_slave6_t19;
+ uint8_t ams_slave6_t20;
+ uint8_t ams_slave6_t21;
+ uint8_t ams_slave6_t22;
+ uint8_t ams_slave6_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave6_t16 = (uint8_t)src_p->ams_slave6_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave6_t16, 0u, 0xffu);
+ ams_slave6_t17 = (uint8_t)src_p->ams_slave6_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave6_t17, 0u, 0xffu);
+ ams_slave6_t18 = (uint8_t)src_p->ams_slave6_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave6_t18, 0u, 0xffu);
+ ams_slave6_t19 = (uint8_t)src_p->ams_slave6_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave6_t19, 0u, 0xffu);
+ ams_slave6_t20 = (uint8_t)src_p->ams_slave6_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave6_t20, 0u, 0xffu);
+ ams_slave6_t21 = (uint8_t)src_p->ams_slave6_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave6_t21, 0u, 0xffu);
+ ams_slave6_t22 = (uint8_t)src_p->ams_slave6_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave6_t22, 0u, 0xffu);
+ ams_slave6_t23 = (uint8_t)src_p->ams_slave6_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave6_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log7_unpack(
+ struct can1__main_ft24_ams_slave6_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t16;
+ uint8_t ams_slave6_t17;
+ uint8_t ams_slave6_t18;
+ uint8_t ams_slave6_t19;
+ uint8_t ams_slave6_t20;
+ uint8_t ams_slave6_t21;
+ uint8_t ams_slave6_t22;
+ uint8_t ams_slave6_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave6_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave6_t16 = (int8_t)ams_slave6_t16;
+ ams_slave6_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_t17 = (int8_t)ams_slave6_t17;
+ ams_slave6_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave6_t18 = (int8_t)ams_slave6_t18;
+ ams_slave6_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_t19 = (int8_t)ams_slave6_t19;
+ ams_slave6_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave6_t20 = (int8_t)ams_slave6_t20;
+ ams_slave6_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_t21 = (int8_t)ams_slave6_t21;
+ ams_slave6_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave6_t22 = (int8_t)ams_slave6_t22;
+ ams_slave6_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave6_t23 = (int8_t)ams_slave6_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log7_init(struct can1__main_ft24_ams_slave6_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log7_ams_slave6_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log7_ams_slave6_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log7_ams_slave6_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave6_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t24;
+ uint8_t ams_slave6_t25;
+ uint8_t ams_slave6_t26;
+ uint8_t ams_slave6_t27;
+ uint8_t ams_slave6_t28;
+ uint8_t ams_slave6_t29;
+ uint8_t ams_slave6_t30;
+ uint8_t ams_slave6_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave6_t24 = (uint8_t)src_p->ams_slave6_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave6_t24, 0u, 0xffu);
+ ams_slave6_t25 = (uint8_t)src_p->ams_slave6_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave6_t25, 0u, 0xffu);
+ ams_slave6_t26 = (uint8_t)src_p->ams_slave6_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave6_t26, 0u, 0xffu);
+ ams_slave6_t27 = (uint8_t)src_p->ams_slave6_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave6_t27, 0u, 0xffu);
+ ams_slave6_t28 = (uint8_t)src_p->ams_slave6_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave6_t28, 0u, 0xffu);
+ ams_slave6_t29 = (uint8_t)src_p->ams_slave6_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave6_t29, 0u, 0xffu);
+ ams_slave6_t30 = (uint8_t)src_p->ams_slave6_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave6_t30, 0u, 0xffu);
+ ams_slave6_t31 = (uint8_t)src_p->ams_slave6_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave6_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_log8_unpack(
+ struct can1__main_ft24_ams_slave6_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave6_t24;
+ uint8_t ams_slave6_t25;
+ uint8_t ams_slave6_t26;
+ uint8_t ams_slave6_t27;
+ uint8_t ams_slave6_t28;
+ uint8_t ams_slave6_t29;
+ uint8_t ams_slave6_t30;
+ uint8_t ams_slave6_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave6_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave6_t24 = (int8_t)ams_slave6_t24;
+ ams_slave6_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave6_t25 = (int8_t)ams_slave6_t25;
+ ams_slave6_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave6_t26 = (int8_t)ams_slave6_t26;
+ ams_slave6_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave6_t27 = (int8_t)ams_slave6_t27;
+ ams_slave6_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave6_t28 = (int8_t)ams_slave6_t28;
+ ams_slave6_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave6_t29 = (int8_t)ams_slave6_t29;
+ ams_slave6_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave6_t30 = (int8_t)ams_slave6_t30;
+ ams_slave6_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave6_t31 = (int8_t)ams_slave6_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_log8_init(struct can1__main_ft24_ams_slave6_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave6_log8_ams_slave6_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_log8_ams_slave6_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_log8_ams_slave6_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave7_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave7_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave7_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave7_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave7_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave7_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave7_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave7_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log0_unpack(
+ struct can1__main_ft24_ams_slave7_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave7_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave7_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave7_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave7_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave7_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log0_init(struct can1__main_ft24_ams_slave7_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log0_ams_slave7_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log0_ams_slave7_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log0_ams_slave7_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave7_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave7_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave7_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave7_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave7_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave7_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave7_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave7_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log1_unpack(
+ struct can1__main_ft24_ams_slave7_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave7_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave7_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave7_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave7_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave7_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log1_init(struct can1__main_ft24_ams_slave7_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log1_ams_slave7_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log1_ams_slave7_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log1_ams_slave7_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave7_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave7_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave7_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave7_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave7_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave7_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave7_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave7_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log2_unpack(
+ struct can1__main_ft24_ams_slave7_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave7_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave7_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave7_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave7_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave7_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log2_init(struct can1__main_ft24_ams_slave7_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log2_ams_slave7_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log2_ams_slave7_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log2_ams_slave7_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave7_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave7_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave7_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave7_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave7_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave7_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave7_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave7_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log3_unpack(
+ struct can1__main_ft24_ams_slave7_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave7_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave7_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave7_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave7_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave7_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log3_init(struct can1__main_ft24_ams_slave7_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave7_log3_ams_slave7_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log3_ams_slave7_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log3_ams_slave7_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave7_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave7_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave7_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave7_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave7_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave7_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave7_log4_unpack(
+ struct can1__main_ft24_ams_slave7_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave7_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave7_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave7_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave7_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave7_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log4_init(struct can1__main_ft24_ams_slave7_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave7_log4_ams_slave7_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_log4_ams_slave7_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_log4_ams_slave7_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave7_log4_ams_slave7_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log4_ams_slave7_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log4_ams_slave7_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t0;
+ uint8_t ams_slave7_t1;
+ uint8_t ams_slave7_t2;
+ uint8_t ams_slave7_t3;
+ uint8_t ams_slave7_t4;
+ uint8_t ams_slave7_t5;
+ uint8_t ams_slave7_t6;
+ uint8_t ams_slave7_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave7_t0 = (uint8_t)src_p->ams_slave7_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave7_t0, 0u, 0xffu);
+ ams_slave7_t1 = (uint8_t)src_p->ams_slave7_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave7_t1, 0u, 0xffu);
+ ams_slave7_t2 = (uint8_t)src_p->ams_slave7_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave7_t2, 0u, 0xffu);
+ ams_slave7_t3 = (uint8_t)src_p->ams_slave7_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave7_t3, 0u, 0xffu);
+ ams_slave7_t4 = (uint8_t)src_p->ams_slave7_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave7_t4, 0u, 0xffu);
+ ams_slave7_t5 = (uint8_t)src_p->ams_slave7_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave7_t5, 0u, 0xffu);
+ ams_slave7_t6 = (uint8_t)src_p->ams_slave7_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave7_t6, 0u, 0xffu);
+ ams_slave7_t7 = (uint8_t)src_p->ams_slave7_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave7_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log5_unpack(
+ struct can1__main_ft24_ams_slave7_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t0;
+ uint8_t ams_slave7_t1;
+ uint8_t ams_slave7_t2;
+ uint8_t ams_slave7_t3;
+ uint8_t ams_slave7_t4;
+ uint8_t ams_slave7_t5;
+ uint8_t ams_slave7_t6;
+ uint8_t ams_slave7_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave7_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave7_t0 = (int8_t)ams_slave7_t0;
+ ams_slave7_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_t1 = (int8_t)ams_slave7_t1;
+ ams_slave7_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave7_t2 = (int8_t)ams_slave7_t2;
+ ams_slave7_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_t3 = (int8_t)ams_slave7_t3;
+ ams_slave7_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave7_t4 = (int8_t)ams_slave7_t4;
+ ams_slave7_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_t5 = (int8_t)ams_slave7_t5;
+ ams_slave7_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave7_t6 = (int8_t)ams_slave7_t6;
+ ams_slave7_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave7_t7 = (int8_t)ams_slave7_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log5_init(struct can1__main_ft24_ams_slave7_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log5_ams_slave7_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log5_ams_slave7_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log5_ams_slave7_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t10;
+ uint8_t ams_slave7_t11;
+ uint8_t ams_slave7_t12;
+ uint8_t ams_slave7_t13;
+ uint8_t ams_slave7_t14;
+ uint8_t ams_slave7_t15;
+ uint8_t ams_slave7_t8;
+ uint8_t ams_slave7_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave7_t8 = (uint8_t)src_p->ams_slave7_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave7_t8, 0u, 0xffu);
+ ams_slave7_t9 = (uint8_t)src_p->ams_slave7_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave7_t9, 0u, 0xffu);
+ ams_slave7_t10 = (uint8_t)src_p->ams_slave7_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave7_t10, 0u, 0xffu);
+ ams_slave7_t11 = (uint8_t)src_p->ams_slave7_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave7_t11, 0u, 0xffu);
+ ams_slave7_t12 = (uint8_t)src_p->ams_slave7_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave7_t12, 0u, 0xffu);
+ ams_slave7_t13 = (uint8_t)src_p->ams_slave7_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave7_t13, 0u, 0xffu);
+ ams_slave7_t14 = (uint8_t)src_p->ams_slave7_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave7_t14, 0u, 0xffu);
+ ams_slave7_t15 = (uint8_t)src_p->ams_slave7_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave7_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log6_unpack(
+ struct can1__main_ft24_ams_slave7_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t10;
+ uint8_t ams_slave7_t11;
+ uint8_t ams_slave7_t12;
+ uint8_t ams_slave7_t13;
+ uint8_t ams_slave7_t14;
+ uint8_t ams_slave7_t15;
+ uint8_t ams_slave7_t8;
+ uint8_t ams_slave7_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave7_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave7_t8 = (int8_t)ams_slave7_t8;
+ ams_slave7_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_t9 = (int8_t)ams_slave7_t9;
+ ams_slave7_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave7_t10 = (int8_t)ams_slave7_t10;
+ ams_slave7_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_t11 = (int8_t)ams_slave7_t11;
+ ams_slave7_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave7_t12 = (int8_t)ams_slave7_t12;
+ ams_slave7_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_t13 = (int8_t)ams_slave7_t13;
+ ams_slave7_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave7_t14 = (int8_t)ams_slave7_t14;
+ ams_slave7_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave7_t15 = (int8_t)ams_slave7_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log6_init(struct can1__main_ft24_ams_slave7_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log6_ams_slave7_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log6_ams_slave7_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log6_ams_slave7_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t16;
+ uint8_t ams_slave7_t17;
+ uint8_t ams_slave7_t18;
+ uint8_t ams_slave7_t19;
+ uint8_t ams_slave7_t20;
+ uint8_t ams_slave7_t21;
+ uint8_t ams_slave7_t22;
+ uint8_t ams_slave7_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave7_t16 = (uint8_t)src_p->ams_slave7_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave7_t16, 0u, 0xffu);
+ ams_slave7_t17 = (uint8_t)src_p->ams_slave7_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave7_t17, 0u, 0xffu);
+ ams_slave7_t18 = (uint8_t)src_p->ams_slave7_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave7_t18, 0u, 0xffu);
+ ams_slave7_t19 = (uint8_t)src_p->ams_slave7_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave7_t19, 0u, 0xffu);
+ ams_slave7_t20 = (uint8_t)src_p->ams_slave7_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave7_t20, 0u, 0xffu);
+ ams_slave7_t21 = (uint8_t)src_p->ams_slave7_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave7_t21, 0u, 0xffu);
+ ams_slave7_t22 = (uint8_t)src_p->ams_slave7_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave7_t22, 0u, 0xffu);
+ ams_slave7_t23 = (uint8_t)src_p->ams_slave7_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave7_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log7_unpack(
+ struct can1__main_ft24_ams_slave7_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t16;
+ uint8_t ams_slave7_t17;
+ uint8_t ams_slave7_t18;
+ uint8_t ams_slave7_t19;
+ uint8_t ams_slave7_t20;
+ uint8_t ams_slave7_t21;
+ uint8_t ams_slave7_t22;
+ uint8_t ams_slave7_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave7_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave7_t16 = (int8_t)ams_slave7_t16;
+ ams_slave7_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_t17 = (int8_t)ams_slave7_t17;
+ ams_slave7_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave7_t18 = (int8_t)ams_slave7_t18;
+ ams_slave7_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_t19 = (int8_t)ams_slave7_t19;
+ ams_slave7_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave7_t20 = (int8_t)ams_slave7_t20;
+ ams_slave7_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_t21 = (int8_t)ams_slave7_t21;
+ ams_slave7_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave7_t22 = (int8_t)ams_slave7_t22;
+ ams_slave7_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave7_t23 = (int8_t)ams_slave7_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log7_init(struct can1__main_ft24_ams_slave7_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log7_ams_slave7_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log7_ams_slave7_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log7_ams_slave7_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave7_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t24;
+ uint8_t ams_slave7_t25;
+ uint8_t ams_slave7_t26;
+ uint8_t ams_slave7_t27;
+ uint8_t ams_slave7_t28;
+ uint8_t ams_slave7_t29;
+ uint8_t ams_slave7_t30;
+ uint8_t ams_slave7_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave7_t24 = (uint8_t)src_p->ams_slave7_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave7_t24, 0u, 0xffu);
+ ams_slave7_t25 = (uint8_t)src_p->ams_slave7_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave7_t25, 0u, 0xffu);
+ ams_slave7_t26 = (uint8_t)src_p->ams_slave7_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave7_t26, 0u, 0xffu);
+ ams_slave7_t27 = (uint8_t)src_p->ams_slave7_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave7_t27, 0u, 0xffu);
+ ams_slave7_t28 = (uint8_t)src_p->ams_slave7_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave7_t28, 0u, 0xffu);
+ ams_slave7_t29 = (uint8_t)src_p->ams_slave7_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave7_t29, 0u, 0xffu);
+ ams_slave7_t30 = (uint8_t)src_p->ams_slave7_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave7_t30, 0u, 0xffu);
+ ams_slave7_t31 = (uint8_t)src_p->ams_slave7_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave7_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_log8_unpack(
+ struct can1__main_ft24_ams_slave7_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave7_t24;
+ uint8_t ams_slave7_t25;
+ uint8_t ams_slave7_t26;
+ uint8_t ams_slave7_t27;
+ uint8_t ams_slave7_t28;
+ uint8_t ams_slave7_t29;
+ uint8_t ams_slave7_t30;
+ uint8_t ams_slave7_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave7_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave7_t24 = (int8_t)ams_slave7_t24;
+ ams_slave7_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave7_t25 = (int8_t)ams_slave7_t25;
+ ams_slave7_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave7_t26 = (int8_t)ams_slave7_t26;
+ ams_slave7_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave7_t27 = (int8_t)ams_slave7_t27;
+ ams_slave7_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave7_t28 = (int8_t)ams_slave7_t28;
+ ams_slave7_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave7_t29 = (int8_t)ams_slave7_t29;
+ ams_slave7_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave7_t30 = (int8_t)ams_slave7_t30;
+ ams_slave7_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave7_t31 = (int8_t)ams_slave7_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_log8_init(struct can1__main_ft24_ams_slave7_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave7_log8_ams_slave7_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_log8_ams_slave7_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_log8_ams_slave7_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave8_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave8_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave8_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave8_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave8_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave8_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave8_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave8_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log0_unpack(
+ struct can1__main_ft24_ams_slave8_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave8_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave8_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave8_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave8_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave8_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log0_init(struct can1__main_ft24_ams_slave8_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log0_ams_slave8_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log0_ams_slave8_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log0_ams_slave8_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave8_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave8_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave8_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave8_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave8_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave8_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave8_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave8_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log1_unpack(
+ struct can1__main_ft24_ams_slave8_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave8_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave8_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave8_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave8_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave8_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log1_init(struct can1__main_ft24_ams_slave8_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log1_ams_slave8_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log1_ams_slave8_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log1_ams_slave8_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave8_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave8_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave8_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave8_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave8_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave8_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave8_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave8_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log2_unpack(
+ struct can1__main_ft24_ams_slave8_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave8_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave8_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave8_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave8_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave8_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log2_init(struct can1__main_ft24_ams_slave8_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log2_ams_slave8_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log2_ams_slave8_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log2_ams_slave8_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave8_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave8_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave8_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave8_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave8_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave8_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave8_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave8_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log3_unpack(
+ struct can1__main_ft24_ams_slave8_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave8_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave8_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave8_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave8_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave8_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log3_init(struct can1__main_ft24_ams_slave8_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave8_log3_ams_slave8_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log3_ams_slave8_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log3_ams_slave8_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave8_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave8_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave8_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave8_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave8_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave8_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave8_log4_unpack(
+ struct can1__main_ft24_ams_slave8_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave8_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave8_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave8_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave8_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave8_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log4_init(struct can1__main_ft24_ams_slave8_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave8_log4_ams_slave8_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_log4_ams_slave8_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_log4_ams_slave8_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave8_log4_ams_slave8_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log4_ams_slave8_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log4_ams_slave8_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t0;
+ uint8_t ams_slave8_t1;
+ uint8_t ams_slave8_t2;
+ uint8_t ams_slave8_t3;
+ uint8_t ams_slave8_t4;
+ uint8_t ams_slave8_t5;
+ uint8_t ams_slave8_t6;
+ uint8_t ams_slave8_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave8_t0 = (uint8_t)src_p->ams_slave8_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave8_t0, 0u, 0xffu);
+ ams_slave8_t1 = (uint8_t)src_p->ams_slave8_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave8_t1, 0u, 0xffu);
+ ams_slave8_t2 = (uint8_t)src_p->ams_slave8_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave8_t2, 0u, 0xffu);
+ ams_slave8_t3 = (uint8_t)src_p->ams_slave8_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave8_t3, 0u, 0xffu);
+ ams_slave8_t4 = (uint8_t)src_p->ams_slave8_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave8_t4, 0u, 0xffu);
+ ams_slave8_t5 = (uint8_t)src_p->ams_slave8_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave8_t5, 0u, 0xffu);
+ ams_slave8_t6 = (uint8_t)src_p->ams_slave8_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave8_t6, 0u, 0xffu);
+ ams_slave8_t7 = (uint8_t)src_p->ams_slave8_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave8_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log5_unpack(
+ struct can1__main_ft24_ams_slave8_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t0;
+ uint8_t ams_slave8_t1;
+ uint8_t ams_slave8_t2;
+ uint8_t ams_slave8_t3;
+ uint8_t ams_slave8_t4;
+ uint8_t ams_slave8_t5;
+ uint8_t ams_slave8_t6;
+ uint8_t ams_slave8_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave8_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave8_t0 = (int8_t)ams_slave8_t0;
+ ams_slave8_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_t1 = (int8_t)ams_slave8_t1;
+ ams_slave8_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave8_t2 = (int8_t)ams_slave8_t2;
+ ams_slave8_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_t3 = (int8_t)ams_slave8_t3;
+ ams_slave8_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave8_t4 = (int8_t)ams_slave8_t4;
+ ams_slave8_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_t5 = (int8_t)ams_slave8_t5;
+ ams_slave8_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave8_t6 = (int8_t)ams_slave8_t6;
+ ams_slave8_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave8_t7 = (int8_t)ams_slave8_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log5_init(struct can1__main_ft24_ams_slave8_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log5_ams_slave8_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log5_ams_slave8_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log5_ams_slave8_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t10;
+ uint8_t ams_slave8_t11;
+ uint8_t ams_slave8_t12;
+ uint8_t ams_slave8_t13;
+ uint8_t ams_slave8_t14;
+ uint8_t ams_slave8_t15;
+ uint8_t ams_slave8_t8;
+ uint8_t ams_slave8_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave8_t8 = (uint8_t)src_p->ams_slave8_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave8_t8, 0u, 0xffu);
+ ams_slave8_t9 = (uint8_t)src_p->ams_slave8_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave8_t9, 0u, 0xffu);
+ ams_slave8_t10 = (uint8_t)src_p->ams_slave8_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave8_t10, 0u, 0xffu);
+ ams_slave8_t11 = (uint8_t)src_p->ams_slave8_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave8_t11, 0u, 0xffu);
+ ams_slave8_t12 = (uint8_t)src_p->ams_slave8_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave8_t12, 0u, 0xffu);
+ ams_slave8_t13 = (uint8_t)src_p->ams_slave8_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave8_t13, 0u, 0xffu);
+ ams_slave8_t14 = (uint8_t)src_p->ams_slave8_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave8_t14, 0u, 0xffu);
+ ams_slave8_t15 = (uint8_t)src_p->ams_slave8_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave8_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log6_unpack(
+ struct can1__main_ft24_ams_slave8_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t10;
+ uint8_t ams_slave8_t11;
+ uint8_t ams_slave8_t12;
+ uint8_t ams_slave8_t13;
+ uint8_t ams_slave8_t14;
+ uint8_t ams_slave8_t15;
+ uint8_t ams_slave8_t8;
+ uint8_t ams_slave8_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave8_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave8_t8 = (int8_t)ams_slave8_t8;
+ ams_slave8_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_t9 = (int8_t)ams_slave8_t9;
+ ams_slave8_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave8_t10 = (int8_t)ams_slave8_t10;
+ ams_slave8_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_t11 = (int8_t)ams_slave8_t11;
+ ams_slave8_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave8_t12 = (int8_t)ams_slave8_t12;
+ ams_slave8_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_t13 = (int8_t)ams_slave8_t13;
+ ams_slave8_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave8_t14 = (int8_t)ams_slave8_t14;
+ ams_slave8_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave8_t15 = (int8_t)ams_slave8_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log6_init(struct can1__main_ft24_ams_slave8_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log6_ams_slave8_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log6_ams_slave8_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log6_ams_slave8_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t16;
+ uint8_t ams_slave8_t17;
+ uint8_t ams_slave8_t18;
+ uint8_t ams_slave8_t19;
+ uint8_t ams_slave8_t20;
+ uint8_t ams_slave8_t21;
+ uint8_t ams_slave8_t22;
+ uint8_t ams_slave8_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave8_t16 = (uint8_t)src_p->ams_slave8_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave8_t16, 0u, 0xffu);
+ ams_slave8_t17 = (uint8_t)src_p->ams_slave8_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave8_t17, 0u, 0xffu);
+ ams_slave8_t18 = (uint8_t)src_p->ams_slave8_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave8_t18, 0u, 0xffu);
+ ams_slave8_t19 = (uint8_t)src_p->ams_slave8_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave8_t19, 0u, 0xffu);
+ ams_slave8_t20 = (uint8_t)src_p->ams_slave8_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave8_t20, 0u, 0xffu);
+ ams_slave8_t21 = (uint8_t)src_p->ams_slave8_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave8_t21, 0u, 0xffu);
+ ams_slave8_t22 = (uint8_t)src_p->ams_slave8_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave8_t22, 0u, 0xffu);
+ ams_slave8_t23 = (uint8_t)src_p->ams_slave8_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave8_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log7_unpack(
+ struct can1__main_ft24_ams_slave8_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t16;
+ uint8_t ams_slave8_t17;
+ uint8_t ams_slave8_t18;
+ uint8_t ams_slave8_t19;
+ uint8_t ams_slave8_t20;
+ uint8_t ams_slave8_t21;
+ uint8_t ams_slave8_t22;
+ uint8_t ams_slave8_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave8_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave8_t16 = (int8_t)ams_slave8_t16;
+ ams_slave8_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_t17 = (int8_t)ams_slave8_t17;
+ ams_slave8_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave8_t18 = (int8_t)ams_slave8_t18;
+ ams_slave8_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_t19 = (int8_t)ams_slave8_t19;
+ ams_slave8_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave8_t20 = (int8_t)ams_slave8_t20;
+ ams_slave8_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_t21 = (int8_t)ams_slave8_t21;
+ ams_slave8_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave8_t22 = (int8_t)ams_slave8_t22;
+ ams_slave8_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave8_t23 = (int8_t)ams_slave8_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log7_init(struct can1__main_ft24_ams_slave8_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log7_ams_slave8_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log7_ams_slave8_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log7_ams_slave8_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave8_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t24;
+ uint8_t ams_slave8_t25;
+ uint8_t ams_slave8_t26;
+ uint8_t ams_slave8_t27;
+ uint8_t ams_slave8_t28;
+ uint8_t ams_slave8_t29;
+ uint8_t ams_slave8_t30;
+ uint8_t ams_slave8_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave8_t24 = (uint8_t)src_p->ams_slave8_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave8_t24, 0u, 0xffu);
+ ams_slave8_t25 = (uint8_t)src_p->ams_slave8_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave8_t25, 0u, 0xffu);
+ ams_slave8_t26 = (uint8_t)src_p->ams_slave8_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave8_t26, 0u, 0xffu);
+ ams_slave8_t27 = (uint8_t)src_p->ams_slave8_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave8_t27, 0u, 0xffu);
+ ams_slave8_t28 = (uint8_t)src_p->ams_slave8_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave8_t28, 0u, 0xffu);
+ ams_slave8_t29 = (uint8_t)src_p->ams_slave8_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave8_t29, 0u, 0xffu);
+ ams_slave8_t30 = (uint8_t)src_p->ams_slave8_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave8_t30, 0u, 0xffu);
+ ams_slave8_t31 = (uint8_t)src_p->ams_slave8_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave8_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_log8_unpack(
+ struct can1__main_ft24_ams_slave8_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave8_t24;
+ uint8_t ams_slave8_t25;
+ uint8_t ams_slave8_t26;
+ uint8_t ams_slave8_t27;
+ uint8_t ams_slave8_t28;
+ uint8_t ams_slave8_t29;
+ uint8_t ams_slave8_t30;
+ uint8_t ams_slave8_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave8_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave8_t24 = (int8_t)ams_slave8_t24;
+ ams_slave8_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave8_t25 = (int8_t)ams_slave8_t25;
+ ams_slave8_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave8_t26 = (int8_t)ams_slave8_t26;
+ ams_slave8_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave8_t27 = (int8_t)ams_slave8_t27;
+ ams_slave8_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave8_t28 = (int8_t)ams_slave8_t28;
+ ams_slave8_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave8_t29 = (int8_t)ams_slave8_t29;
+ ams_slave8_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave8_t30 = (int8_t)ams_slave8_t30;
+ ams_slave8_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave8_t31 = (int8_t)ams_slave8_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_log8_init(struct can1__main_ft24_ams_slave8_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave8_log8_ams_slave8_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_log8_ams_slave8_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_log8_ams_slave8_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave9_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave9_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave9_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave9_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave9_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave9_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave9_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave9_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log0_unpack(
+ struct can1__main_ft24_ams_slave9_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave9_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave9_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave9_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave9_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave9_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log0_init(struct can1__main_ft24_ams_slave9_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log0_ams_slave9_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log0_ams_slave9_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log0_ams_slave9_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave9_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave9_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave9_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave9_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave9_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave9_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave9_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave9_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log1_unpack(
+ struct can1__main_ft24_ams_slave9_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave9_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave9_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave9_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave9_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave9_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log1_init(struct can1__main_ft24_ams_slave9_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log1_ams_slave9_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log1_ams_slave9_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log1_ams_slave9_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave9_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave9_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave9_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave9_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave9_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave9_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave9_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave9_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log2_unpack(
+ struct can1__main_ft24_ams_slave9_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave9_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave9_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave9_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave9_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave9_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log2_init(struct can1__main_ft24_ams_slave9_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log2_ams_slave9_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log2_ams_slave9_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log2_ams_slave9_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave9_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave9_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave9_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave9_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave9_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave9_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave9_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave9_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log3_unpack(
+ struct can1__main_ft24_ams_slave9_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave9_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave9_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave9_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave9_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave9_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log3_init(struct can1__main_ft24_ams_slave9_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave9_log3_ams_slave9_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log3_ams_slave9_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log3_ams_slave9_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave9_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave9_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave9_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave9_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave9_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave9_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave9_log4_unpack(
+ struct can1__main_ft24_ams_slave9_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave9_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave9_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave9_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave9_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave9_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log4_init(struct can1__main_ft24_ams_slave9_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave9_log4_ams_slave9_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_log4_ams_slave9_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_log4_ams_slave9_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave9_log4_ams_slave9_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log4_ams_slave9_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log4_ams_slave9_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t0;
+ uint8_t ams_slave9_t1;
+ uint8_t ams_slave9_t2;
+ uint8_t ams_slave9_t3;
+ uint8_t ams_slave9_t4;
+ uint8_t ams_slave9_t5;
+ uint8_t ams_slave9_t6;
+ uint8_t ams_slave9_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave9_t0 = (uint8_t)src_p->ams_slave9_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave9_t0, 0u, 0xffu);
+ ams_slave9_t1 = (uint8_t)src_p->ams_slave9_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave9_t1, 0u, 0xffu);
+ ams_slave9_t2 = (uint8_t)src_p->ams_slave9_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave9_t2, 0u, 0xffu);
+ ams_slave9_t3 = (uint8_t)src_p->ams_slave9_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave9_t3, 0u, 0xffu);
+ ams_slave9_t4 = (uint8_t)src_p->ams_slave9_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave9_t4, 0u, 0xffu);
+ ams_slave9_t5 = (uint8_t)src_p->ams_slave9_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave9_t5, 0u, 0xffu);
+ ams_slave9_t6 = (uint8_t)src_p->ams_slave9_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave9_t6, 0u, 0xffu);
+ ams_slave9_t7 = (uint8_t)src_p->ams_slave9_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave9_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log5_unpack(
+ struct can1__main_ft24_ams_slave9_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t0;
+ uint8_t ams_slave9_t1;
+ uint8_t ams_slave9_t2;
+ uint8_t ams_slave9_t3;
+ uint8_t ams_slave9_t4;
+ uint8_t ams_slave9_t5;
+ uint8_t ams_slave9_t6;
+ uint8_t ams_slave9_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave9_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave9_t0 = (int8_t)ams_slave9_t0;
+ ams_slave9_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_t1 = (int8_t)ams_slave9_t1;
+ ams_slave9_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave9_t2 = (int8_t)ams_slave9_t2;
+ ams_slave9_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_t3 = (int8_t)ams_slave9_t3;
+ ams_slave9_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave9_t4 = (int8_t)ams_slave9_t4;
+ ams_slave9_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_t5 = (int8_t)ams_slave9_t5;
+ ams_slave9_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave9_t6 = (int8_t)ams_slave9_t6;
+ ams_slave9_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave9_t7 = (int8_t)ams_slave9_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log5_init(struct can1__main_ft24_ams_slave9_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log5_ams_slave9_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log5_ams_slave9_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log5_ams_slave9_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t10;
+ uint8_t ams_slave9_t11;
+ uint8_t ams_slave9_t12;
+ uint8_t ams_slave9_t13;
+ uint8_t ams_slave9_t14;
+ uint8_t ams_slave9_t15;
+ uint8_t ams_slave9_t8;
+ uint8_t ams_slave9_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave9_t8 = (uint8_t)src_p->ams_slave9_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave9_t8, 0u, 0xffu);
+ ams_slave9_t9 = (uint8_t)src_p->ams_slave9_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave9_t9, 0u, 0xffu);
+ ams_slave9_t10 = (uint8_t)src_p->ams_slave9_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave9_t10, 0u, 0xffu);
+ ams_slave9_t11 = (uint8_t)src_p->ams_slave9_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave9_t11, 0u, 0xffu);
+ ams_slave9_t12 = (uint8_t)src_p->ams_slave9_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave9_t12, 0u, 0xffu);
+ ams_slave9_t13 = (uint8_t)src_p->ams_slave9_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave9_t13, 0u, 0xffu);
+ ams_slave9_t14 = (uint8_t)src_p->ams_slave9_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave9_t14, 0u, 0xffu);
+ ams_slave9_t15 = (uint8_t)src_p->ams_slave9_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave9_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log6_unpack(
+ struct can1__main_ft24_ams_slave9_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t10;
+ uint8_t ams_slave9_t11;
+ uint8_t ams_slave9_t12;
+ uint8_t ams_slave9_t13;
+ uint8_t ams_slave9_t14;
+ uint8_t ams_slave9_t15;
+ uint8_t ams_slave9_t8;
+ uint8_t ams_slave9_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave9_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave9_t8 = (int8_t)ams_slave9_t8;
+ ams_slave9_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_t9 = (int8_t)ams_slave9_t9;
+ ams_slave9_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave9_t10 = (int8_t)ams_slave9_t10;
+ ams_slave9_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_t11 = (int8_t)ams_slave9_t11;
+ ams_slave9_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave9_t12 = (int8_t)ams_slave9_t12;
+ ams_slave9_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_t13 = (int8_t)ams_slave9_t13;
+ ams_slave9_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave9_t14 = (int8_t)ams_slave9_t14;
+ ams_slave9_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave9_t15 = (int8_t)ams_slave9_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log6_init(struct can1__main_ft24_ams_slave9_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log6_ams_slave9_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log6_ams_slave9_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log6_ams_slave9_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t16;
+ uint8_t ams_slave9_t17;
+ uint8_t ams_slave9_t18;
+ uint8_t ams_slave9_t19;
+ uint8_t ams_slave9_t20;
+ uint8_t ams_slave9_t21;
+ uint8_t ams_slave9_t22;
+ uint8_t ams_slave9_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave9_t16 = (uint8_t)src_p->ams_slave9_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave9_t16, 0u, 0xffu);
+ ams_slave9_t17 = (uint8_t)src_p->ams_slave9_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave9_t17, 0u, 0xffu);
+ ams_slave9_t18 = (uint8_t)src_p->ams_slave9_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave9_t18, 0u, 0xffu);
+ ams_slave9_t19 = (uint8_t)src_p->ams_slave9_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave9_t19, 0u, 0xffu);
+ ams_slave9_t20 = (uint8_t)src_p->ams_slave9_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave9_t20, 0u, 0xffu);
+ ams_slave9_t21 = (uint8_t)src_p->ams_slave9_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave9_t21, 0u, 0xffu);
+ ams_slave9_t22 = (uint8_t)src_p->ams_slave9_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave9_t22, 0u, 0xffu);
+ ams_slave9_t23 = (uint8_t)src_p->ams_slave9_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave9_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log7_unpack(
+ struct can1__main_ft24_ams_slave9_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t16;
+ uint8_t ams_slave9_t17;
+ uint8_t ams_slave9_t18;
+ uint8_t ams_slave9_t19;
+ uint8_t ams_slave9_t20;
+ uint8_t ams_slave9_t21;
+ uint8_t ams_slave9_t22;
+ uint8_t ams_slave9_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave9_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave9_t16 = (int8_t)ams_slave9_t16;
+ ams_slave9_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_t17 = (int8_t)ams_slave9_t17;
+ ams_slave9_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave9_t18 = (int8_t)ams_slave9_t18;
+ ams_slave9_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_t19 = (int8_t)ams_slave9_t19;
+ ams_slave9_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave9_t20 = (int8_t)ams_slave9_t20;
+ ams_slave9_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_t21 = (int8_t)ams_slave9_t21;
+ ams_slave9_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave9_t22 = (int8_t)ams_slave9_t22;
+ ams_slave9_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave9_t23 = (int8_t)ams_slave9_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log7_init(struct can1__main_ft24_ams_slave9_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log7_ams_slave9_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log7_ams_slave9_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log7_ams_slave9_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave9_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t24;
+ uint8_t ams_slave9_t25;
+ uint8_t ams_slave9_t26;
+ uint8_t ams_slave9_t27;
+ uint8_t ams_slave9_t28;
+ uint8_t ams_slave9_t29;
+ uint8_t ams_slave9_t30;
+ uint8_t ams_slave9_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave9_t24 = (uint8_t)src_p->ams_slave9_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave9_t24, 0u, 0xffu);
+ ams_slave9_t25 = (uint8_t)src_p->ams_slave9_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave9_t25, 0u, 0xffu);
+ ams_slave9_t26 = (uint8_t)src_p->ams_slave9_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave9_t26, 0u, 0xffu);
+ ams_slave9_t27 = (uint8_t)src_p->ams_slave9_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave9_t27, 0u, 0xffu);
+ ams_slave9_t28 = (uint8_t)src_p->ams_slave9_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave9_t28, 0u, 0xffu);
+ ams_slave9_t29 = (uint8_t)src_p->ams_slave9_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave9_t29, 0u, 0xffu);
+ ams_slave9_t30 = (uint8_t)src_p->ams_slave9_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave9_t30, 0u, 0xffu);
+ ams_slave9_t31 = (uint8_t)src_p->ams_slave9_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave9_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_log8_unpack(
+ struct can1__main_ft24_ams_slave9_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave9_t24;
+ uint8_t ams_slave9_t25;
+ uint8_t ams_slave9_t26;
+ uint8_t ams_slave9_t27;
+ uint8_t ams_slave9_t28;
+ uint8_t ams_slave9_t29;
+ uint8_t ams_slave9_t30;
+ uint8_t ams_slave9_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave9_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave9_t24 = (int8_t)ams_slave9_t24;
+ ams_slave9_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave9_t25 = (int8_t)ams_slave9_t25;
+ ams_slave9_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave9_t26 = (int8_t)ams_slave9_t26;
+ ams_slave9_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave9_t27 = (int8_t)ams_slave9_t27;
+ ams_slave9_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave9_t28 = (int8_t)ams_slave9_t28;
+ ams_slave9_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave9_t29 = (int8_t)ams_slave9_t29;
+ ams_slave9_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave9_t30 = (int8_t)ams_slave9_t30;
+ ams_slave9_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave9_t31 = (int8_t)ams_slave9_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_log8_init(struct can1__main_ft24_ams_slave9_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave9_log8_ams_slave9_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_log8_ams_slave9_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_log8_ams_slave9_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave10_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave10_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave10_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave10_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave10_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave10_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave10_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave10_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log0_unpack(
+ struct can1__main_ft24_ams_slave10_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave10_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave10_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave10_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave10_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave10_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log0_init(struct can1__main_ft24_ams_slave10_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log0_ams_slave10_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log0_ams_slave10_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log0_ams_slave10_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave10_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave10_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave10_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave10_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave10_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave10_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave10_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave10_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log1_unpack(
+ struct can1__main_ft24_ams_slave10_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave10_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave10_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave10_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave10_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave10_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log1_init(struct can1__main_ft24_ams_slave10_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log1_ams_slave10_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log1_ams_slave10_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log1_ams_slave10_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave10_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave10_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave10_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave10_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave10_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave10_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave10_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave10_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log2_unpack(
+ struct can1__main_ft24_ams_slave10_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave10_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave10_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave10_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave10_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave10_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log2_init(struct can1__main_ft24_ams_slave10_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log2_ams_slave10_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log2_ams_slave10_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log2_ams_slave10_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave10_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave10_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave10_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave10_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave10_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave10_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave10_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave10_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log3_unpack(
+ struct can1__main_ft24_ams_slave10_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave10_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave10_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave10_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave10_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave10_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log3_init(struct can1__main_ft24_ams_slave10_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave10_log3_ams_slave10_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log3_ams_slave10_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log3_ams_slave10_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave10_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave10_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave10_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave10_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave10_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave10_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave10_log4_unpack(
+ struct can1__main_ft24_ams_slave10_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave10_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave10_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave10_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave10_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave10_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log4_init(struct can1__main_ft24_ams_slave10_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave10_log4_ams_slave10_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_log4_ams_slave10_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_log4_ams_slave10_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave10_log4_ams_slave10_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log4_ams_slave10_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log4_ams_slave10_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t0;
+ uint8_t ams_slave10_t1;
+ uint8_t ams_slave10_t2;
+ uint8_t ams_slave10_t3;
+ uint8_t ams_slave10_t4;
+ uint8_t ams_slave10_t5;
+ uint8_t ams_slave10_t6;
+ uint8_t ams_slave10_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave10_t0 = (uint8_t)src_p->ams_slave10_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave10_t0, 0u, 0xffu);
+ ams_slave10_t1 = (uint8_t)src_p->ams_slave10_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave10_t1, 0u, 0xffu);
+ ams_slave10_t2 = (uint8_t)src_p->ams_slave10_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave10_t2, 0u, 0xffu);
+ ams_slave10_t3 = (uint8_t)src_p->ams_slave10_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave10_t3, 0u, 0xffu);
+ ams_slave10_t4 = (uint8_t)src_p->ams_slave10_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave10_t4, 0u, 0xffu);
+ ams_slave10_t5 = (uint8_t)src_p->ams_slave10_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave10_t5, 0u, 0xffu);
+ ams_slave10_t6 = (uint8_t)src_p->ams_slave10_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave10_t6, 0u, 0xffu);
+ ams_slave10_t7 = (uint8_t)src_p->ams_slave10_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave10_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log5_unpack(
+ struct can1__main_ft24_ams_slave10_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t0;
+ uint8_t ams_slave10_t1;
+ uint8_t ams_slave10_t2;
+ uint8_t ams_slave10_t3;
+ uint8_t ams_slave10_t4;
+ uint8_t ams_slave10_t5;
+ uint8_t ams_slave10_t6;
+ uint8_t ams_slave10_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave10_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave10_t0 = (int8_t)ams_slave10_t0;
+ ams_slave10_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_t1 = (int8_t)ams_slave10_t1;
+ ams_slave10_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave10_t2 = (int8_t)ams_slave10_t2;
+ ams_slave10_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_t3 = (int8_t)ams_slave10_t3;
+ ams_slave10_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave10_t4 = (int8_t)ams_slave10_t4;
+ ams_slave10_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_t5 = (int8_t)ams_slave10_t5;
+ ams_slave10_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave10_t6 = (int8_t)ams_slave10_t6;
+ ams_slave10_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave10_t7 = (int8_t)ams_slave10_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log5_init(struct can1__main_ft24_ams_slave10_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log5_ams_slave10_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log5_ams_slave10_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log5_ams_slave10_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t10;
+ uint8_t ams_slave10_t11;
+ uint8_t ams_slave10_t12;
+ uint8_t ams_slave10_t13;
+ uint8_t ams_slave10_t14;
+ uint8_t ams_slave10_t15;
+ uint8_t ams_slave10_t8;
+ uint8_t ams_slave10_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave10_t8 = (uint8_t)src_p->ams_slave10_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave10_t8, 0u, 0xffu);
+ ams_slave10_t9 = (uint8_t)src_p->ams_slave10_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave10_t9, 0u, 0xffu);
+ ams_slave10_t10 = (uint8_t)src_p->ams_slave10_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave10_t10, 0u, 0xffu);
+ ams_slave10_t11 = (uint8_t)src_p->ams_slave10_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave10_t11, 0u, 0xffu);
+ ams_slave10_t12 = (uint8_t)src_p->ams_slave10_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave10_t12, 0u, 0xffu);
+ ams_slave10_t13 = (uint8_t)src_p->ams_slave10_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave10_t13, 0u, 0xffu);
+ ams_slave10_t14 = (uint8_t)src_p->ams_slave10_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave10_t14, 0u, 0xffu);
+ ams_slave10_t15 = (uint8_t)src_p->ams_slave10_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave10_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log6_unpack(
+ struct can1__main_ft24_ams_slave10_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t10;
+ uint8_t ams_slave10_t11;
+ uint8_t ams_slave10_t12;
+ uint8_t ams_slave10_t13;
+ uint8_t ams_slave10_t14;
+ uint8_t ams_slave10_t15;
+ uint8_t ams_slave10_t8;
+ uint8_t ams_slave10_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave10_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave10_t8 = (int8_t)ams_slave10_t8;
+ ams_slave10_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_t9 = (int8_t)ams_slave10_t9;
+ ams_slave10_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave10_t10 = (int8_t)ams_slave10_t10;
+ ams_slave10_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_t11 = (int8_t)ams_slave10_t11;
+ ams_slave10_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave10_t12 = (int8_t)ams_slave10_t12;
+ ams_slave10_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_t13 = (int8_t)ams_slave10_t13;
+ ams_slave10_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave10_t14 = (int8_t)ams_slave10_t14;
+ ams_slave10_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave10_t15 = (int8_t)ams_slave10_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log6_init(struct can1__main_ft24_ams_slave10_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log6_ams_slave10_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log6_ams_slave10_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log6_ams_slave10_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t16;
+ uint8_t ams_slave10_t17;
+ uint8_t ams_slave10_t18;
+ uint8_t ams_slave10_t19;
+ uint8_t ams_slave10_t20;
+ uint8_t ams_slave10_t21;
+ uint8_t ams_slave10_t22;
+ uint8_t ams_slave10_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave10_t16 = (uint8_t)src_p->ams_slave10_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave10_t16, 0u, 0xffu);
+ ams_slave10_t17 = (uint8_t)src_p->ams_slave10_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave10_t17, 0u, 0xffu);
+ ams_slave10_t18 = (uint8_t)src_p->ams_slave10_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave10_t18, 0u, 0xffu);
+ ams_slave10_t19 = (uint8_t)src_p->ams_slave10_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave10_t19, 0u, 0xffu);
+ ams_slave10_t20 = (uint8_t)src_p->ams_slave10_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave10_t20, 0u, 0xffu);
+ ams_slave10_t21 = (uint8_t)src_p->ams_slave10_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave10_t21, 0u, 0xffu);
+ ams_slave10_t22 = (uint8_t)src_p->ams_slave10_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave10_t22, 0u, 0xffu);
+ ams_slave10_t23 = (uint8_t)src_p->ams_slave10_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave10_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log7_unpack(
+ struct can1__main_ft24_ams_slave10_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t16;
+ uint8_t ams_slave10_t17;
+ uint8_t ams_slave10_t18;
+ uint8_t ams_slave10_t19;
+ uint8_t ams_slave10_t20;
+ uint8_t ams_slave10_t21;
+ uint8_t ams_slave10_t22;
+ uint8_t ams_slave10_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave10_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave10_t16 = (int8_t)ams_slave10_t16;
+ ams_slave10_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_t17 = (int8_t)ams_slave10_t17;
+ ams_slave10_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave10_t18 = (int8_t)ams_slave10_t18;
+ ams_slave10_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_t19 = (int8_t)ams_slave10_t19;
+ ams_slave10_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave10_t20 = (int8_t)ams_slave10_t20;
+ ams_slave10_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_t21 = (int8_t)ams_slave10_t21;
+ ams_slave10_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave10_t22 = (int8_t)ams_slave10_t22;
+ ams_slave10_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave10_t23 = (int8_t)ams_slave10_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log7_init(struct can1__main_ft24_ams_slave10_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log7_ams_slave10_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log7_ams_slave10_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log7_ams_slave10_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave10_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t24;
+ uint8_t ams_slave10_t25;
+ uint8_t ams_slave10_t26;
+ uint8_t ams_slave10_t27;
+ uint8_t ams_slave10_t28;
+ uint8_t ams_slave10_t29;
+ uint8_t ams_slave10_t30;
+ uint8_t ams_slave10_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave10_t24 = (uint8_t)src_p->ams_slave10_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave10_t24, 0u, 0xffu);
+ ams_slave10_t25 = (uint8_t)src_p->ams_slave10_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave10_t25, 0u, 0xffu);
+ ams_slave10_t26 = (uint8_t)src_p->ams_slave10_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave10_t26, 0u, 0xffu);
+ ams_slave10_t27 = (uint8_t)src_p->ams_slave10_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave10_t27, 0u, 0xffu);
+ ams_slave10_t28 = (uint8_t)src_p->ams_slave10_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave10_t28, 0u, 0xffu);
+ ams_slave10_t29 = (uint8_t)src_p->ams_slave10_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave10_t29, 0u, 0xffu);
+ ams_slave10_t30 = (uint8_t)src_p->ams_slave10_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave10_t30, 0u, 0xffu);
+ ams_slave10_t31 = (uint8_t)src_p->ams_slave10_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave10_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_log8_unpack(
+ struct can1__main_ft24_ams_slave10_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave10_t24;
+ uint8_t ams_slave10_t25;
+ uint8_t ams_slave10_t26;
+ uint8_t ams_slave10_t27;
+ uint8_t ams_slave10_t28;
+ uint8_t ams_slave10_t29;
+ uint8_t ams_slave10_t30;
+ uint8_t ams_slave10_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave10_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave10_t24 = (int8_t)ams_slave10_t24;
+ ams_slave10_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave10_t25 = (int8_t)ams_slave10_t25;
+ ams_slave10_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave10_t26 = (int8_t)ams_slave10_t26;
+ ams_slave10_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave10_t27 = (int8_t)ams_slave10_t27;
+ ams_slave10_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave10_t28 = (int8_t)ams_slave10_t28;
+ ams_slave10_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave10_t29 = (int8_t)ams_slave10_t29;
+ ams_slave10_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave10_t30 = (int8_t)ams_slave10_t30;
+ ams_slave10_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave10_t31 = (int8_t)ams_slave10_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_log8_init(struct can1__main_ft24_ams_slave10_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave10_log8_ams_slave10_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_log8_ams_slave10_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_log8_ams_slave10_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave11_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave11_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave11_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave11_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave11_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave11_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave11_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave11_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log0_unpack(
+ struct can1__main_ft24_ams_slave11_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave11_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave11_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave11_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave11_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave11_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log0_init(struct can1__main_ft24_ams_slave11_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log0_ams_slave11_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log0_ams_slave11_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log0_ams_slave11_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave11_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave11_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave11_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave11_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave11_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave11_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave11_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave11_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log1_unpack(
+ struct can1__main_ft24_ams_slave11_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave11_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave11_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave11_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave11_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave11_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log1_init(struct can1__main_ft24_ams_slave11_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log1_ams_slave11_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log1_ams_slave11_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log1_ams_slave11_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave11_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave11_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave11_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave11_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave11_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave11_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave11_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave11_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log2_unpack(
+ struct can1__main_ft24_ams_slave11_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave11_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave11_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave11_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave11_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave11_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log2_init(struct can1__main_ft24_ams_slave11_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log2_ams_slave11_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log2_ams_slave11_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log2_ams_slave11_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave11_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave11_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave11_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave11_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave11_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave11_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave11_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave11_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log3_unpack(
+ struct can1__main_ft24_ams_slave11_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave11_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave11_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave11_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave11_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave11_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log3_init(struct can1__main_ft24_ams_slave11_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave11_log3_ams_slave11_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log3_ams_slave11_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log3_ams_slave11_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave11_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave11_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave11_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave11_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave11_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave11_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave11_log4_unpack(
+ struct can1__main_ft24_ams_slave11_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave11_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave11_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave11_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave11_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave11_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log4_init(struct can1__main_ft24_ams_slave11_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave11_log4_ams_slave11_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_log4_ams_slave11_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_log4_ams_slave11_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave11_log4_ams_slave11_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log4_ams_slave11_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log4_ams_slave11_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t0;
+ uint8_t ams_slave11_t1;
+ uint8_t ams_slave11_t2;
+ uint8_t ams_slave11_t3;
+ uint8_t ams_slave11_t4;
+ uint8_t ams_slave11_t5;
+ uint8_t ams_slave11_t6;
+ uint8_t ams_slave11_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave11_t0 = (uint8_t)src_p->ams_slave11_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave11_t0, 0u, 0xffu);
+ ams_slave11_t1 = (uint8_t)src_p->ams_slave11_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave11_t1, 0u, 0xffu);
+ ams_slave11_t2 = (uint8_t)src_p->ams_slave11_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave11_t2, 0u, 0xffu);
+ ams_slave11_t3 = (uint8_t)src_p->ams_slave11_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave11_t3, 0u, 0xffu);
+ ams_slave11_t4 = (uint8_t)src_p->ams_slave11_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave11_t4, 0u, 0xffu);
+ ams_slave11_t5 = (uint8_t)src_p->ams_slave11_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave11_t5, 0u, 0xffu);
+ ams_slave11_t6 = (uint8_t)src_p->ams_slave11_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave11_t6, 0u, 0xffu);
+ ams_slave11_t7 = (uint8_t)src_p->ams_slave11_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave11_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log5_unpack(
+ struct can1__main_ft24_ams_slave11_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t0;
+ uint8_t ams_slave11_t1;
+ uint8_t ams_slave11_t2;
+ uint8_t ams_slave11_t3;
+ uint8_t ams_slave11_t4;
+ uint8_t ams_slave11_t5;
+ uint8_t ams_slave11_t6;
+ uint8_t ams_slave11_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave11_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave11_t0 = (int8_t)ams_slave11_t0;
+ ams_slave11_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_t1 = (int8_t)ams_slave11_t1;
+ ams_slave11_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave11_t2 = (int8_t)ams_slave11_t2;
+ ams_slave11_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_t3 = (int8_t)ams_slave11_t3;
+ ams_slave11_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave11_t4 = (int8_t)ams_slave11_t4;
+ ams_slave11_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_t5 = (int8_t)ams_slave11_t5;
+ ams_slave11_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave11_t6 = (int8_t)ams_slave11_t6;
+ ams_slave11_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave11_t7 = (int8_t)ams_slave11_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log5_init(struct can1__main_ft24_ams_slave11_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log5_ams_slave11_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log5_ams_slave11_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log5_ams_slave11_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t10;
+ uint8_t ams_slave11_t11;
+ uint8_t ams_slave11_t12;
+ uint8_t ams_slave11_t13;
+ uint8_t ams_slave11_t14;
+ uint8_t ams_slave11_t15;
+ uint8_t ams_slave11_t8;
+ uint8_t ams_slave11_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave11_t8 = (uint8_t)src_p->ams_slave11_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave11_t8, 0u, 0xffu);
+ ams_slave11_t9 = (uint8_t)src_p->ams_slave11_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave11_t9, 0u, 0xffu);
+ ams_slave11_t10 = (uint8_t)src_p->ams_slave11_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave11_t10, 0u, 0xffu);
+ ams_slave11_t11 = (uint8_t)src_p->ams_slave11_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave11_t11, 0u, 0xffu);
+ ams_slave11_t12 = (uint8_t)src_p->ams_slave11_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave11_t12, 0u, 0xffu);
+ ams_slave11_t13 = (uint8_t)src_p->ams_slave11_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave11_t13, 0u, 0xffu);
+ ams_slave11_t14 = (uint8_t)src_p->ams_slave11_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave11_t14, 0u, 0xffu);
+ ams_slave11_t15 = (uint8_t)src_p->ams_slave11_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave11_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log6_unpack(
+ struct can1__main_ft24_ams_slave11_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t10;
+ uint8_t ams_slave11_t11;
+ uint8_t ams_slave11_t12;
+ uint8_t ams_slave11_t13;
+ uint8_t ams_slave11_t14;
+ uint8_t ams_slave11_t15;
+ uint8_t ams_slave11_t8;
+ uint8_t ams_slave11_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave11_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave11_t8 = (int8_t)ams_slave11_t8;
+ ams_slave11_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_t9 = (int8_t)ams_slave11_t9;
+ ams_slave11_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave11_t10 = (int8_t)ams_slave11_t10;
+ ams_slave11_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_t11 = (int8_t)ams_slave11_t11;
+ ams_slave11_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave11_t12 = (int8_t)ams_slave11_t12;
+ ams_slave11_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_t13 = (int8_t)ams_slave11_t13;
+ ams_slave11_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave11_t14 = (int8_t)ams_slave11_t14;
+ ams_slave11_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave11_t15 = (int8_t)ams_slave11_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log6_init(struct can1__main_ft24_ams_slave11_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log6_ams_slave11_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log6_ams_slave11_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log6_ams_slave11_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t16;
+ uint8_t ams_slave11_t17;
+ uint8_t ams_slave11_t18;
+ uint8_t ams_slave11_t19;
+ uint8_t ams_slave11_t20;
+ uint8_t ams_slave11_t21;
+ uint8_t ams_slave11_t22;
+ uint8_t ams_slave11_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave11_t16 = (uint8_t)src_p->ams_slave11_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave11_t16, 0u, 0xffu);
+ ams_slave11_t17 = (uint8_t)src_p->ams_slave11_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave11_t17, 0u, 0xffu);
+ ams_slave11_t18 = (uint8_t)src_p->ams_slave11_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave11_t18, 0u, 0xffu);
+ ams_slave11_t19 = (uint8_t)src_p->ams_slave11_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave11_t19, 0u, 0xffu);
+ ams_slave11_t20 = (uint8_t)src_p->ams_slave11_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave11_t20, 0u, 0xffu);
+ ams_slave11_t21 = (uint8_t)src_p->ams_slave11_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave11_t21, 0u, 0xffu);
+ ams_slave11_t22 = (uint8_t)src_p->ams_slave11_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave11_t22, 0u, 0xffu);
+ ams_slave11_t23 = (uint8_t)src_p->ams_slave11_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave11_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log7_unpack(
+ struct can1__main_ft24_ams_slave11_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t16;
+ uint8_t ams_slave11_t17;
+ uint8_t ams_slave11_t18;
+ uint8_t ams_slave11_t19;
+ uint8_t ams_slave11_t20;
+ uint8_t ams_slave11_t21;
+ uint8_t ams_slave11_t22;
+ uint8_t ams_slave11_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave11_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave11_t16 = (int8_t)ams_slave11_t16;
+ ams_slave11_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_t17 = (int8_t)ams_slave11_t17;
+ ams_slave11_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave11_t18 = (int8_t)ams_slave11_t18;
+ ams_slave11_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_t19 = (int8_t)ams_slave11_t19;
+ ams_slave11_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave11_t20 = (int8_t)ams_slave11_t20;
+ ams_slave11_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_t21 = (int8_t)ams_slave11_t21;
+ ams_slave11_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave11_t22 = (int8_t)ams_slave11_t22;
+ ams_slave11_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave11_t23 = (int8_t)ams_slave11_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log7_init(struct can1__main_ft24_ams_slave11_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log7_ams_slave11_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log7_ams_slave11_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log7_ams_slave11_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave11_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t24;
+ uint8_t ams_slave11_t25;
+ uint8_t ams_slave11_t26;
+ uint8_t ams_slave11_t27;
+ uint8_t ams_slave11_t28;
+ uint8_t ams_slave11_t29;
+ uint8_t ams_slave11_t30;
+ uint8_t ams_slave11_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave11_t24 = (uint8_t)src_p->ams_slave11_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave11_t24, 0u, 0xffu);
+ ams_slave11_t25 = (uint8_t)src_p->ams_slave11_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave11_t25, 0u, 0xffu);
+ ams_slave11_t26 = (uint8_t)src_p->ams_slave11_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave11_t26, 0u, 0xffu);
+ ams_slave11_t27 = (uint8_t)src_p->ams_slave11_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave11_t27, 0u, 0xffu);
+ ams_slave11_t28 = (uint8_t)src_p->ams_slave11_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave11_t28, 0u, 0xffu);
+ ams_slave11_t29 = (uint8_t)src_p->ams_slave11_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave11_t29, 0u, 0xffu);
+ ams_slave11_t30 = (uint8_t)src_p->ams_slave11_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave11_t30, 0u, 0xffu);
+ ams_slave11_t31 = (uint8_t)src_p->ams_slave11_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave11_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_log8_unpack(
+ struct can1__main_ft24_ams_slave11_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave11_t24;
+ uint8_t ams_slave11_t25;
+ uint8_t ams_slave11_t26;
+ uint8_t ams_slave11_t27;
+ uint8_t ams_slave11_t28;
+ uint8_t ams_slave11_t29;
+ uint8_t ams_slave11_t30;
+ uint8_t ams_slave11_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave11_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave11_t24 = (int8_t)ams_slave11_t24;
+ ams_slave11_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave11_t25 = (int8_t)ams_slave11_t25;
+ ams_slave11_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave11_t26 = (int8_t)ams_slave11_t26;
+ ams_slave11_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave11_t27 = (int8_t)ams_slave11_t27;
+ ams_slave11_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave11_t28 = (int8_t)ams_slave11_t28;
+ ams_slave11_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave11_t29 = (int8_t)ams_slave11_t29;
+ ams_slave11_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave11_t30 = (int8_t)ams_slave11_t30;
+ ams_slave11_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave11_t31 = (int8_t)ams_slave11_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_log8_init(struct can1__main_ft24_ams_slave11_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave11_log8_ams_slave11_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_log8_ams_slave11_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_log8_ams_slave11_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave12_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave12_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave12_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave12_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave12_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave12_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave12_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave12_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log0_unpack(
+ struct can1__main_ft24_ams_slave12_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave12_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave12_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave12_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave12_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave12_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log0_init(struct can1__main_ft24_ams_slave12_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log0_ams_slave12_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log0_ams_slave12_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log0_ams_slave12_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave12_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave12_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave12_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave12_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave12_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave12_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave12_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave12_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log1_unpack(
+ struct can1__main_ft24_ams_slave12_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave12_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave12_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave12_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave12_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave12_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log1_init(struct can1__main_ft24_ams_slave12_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log1_ams_slave12_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log1_ams_slave12_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log1_ams_slave12_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave12_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave12_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave12_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave12_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave12_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave12_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave12_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave12_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log2_unpack(
+ struct can1__main_ft24_ams_slave12_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave12_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave12_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave12_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave12_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave12_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log2_init(struct can1__main_ft24_ams_slave12_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log2_ams_slave12_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log2_ams_slave12_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log2_ams_slave12_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave12_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave12_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave12_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave12_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave12_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave12_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave12_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave12_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log3_unpack(
+ struct can1__main_ft24_ams_slave12_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave12_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave12_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave12_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave12_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave12_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log3_init(struct can1__main_ft24_ams_slave12_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave12_log3_ams_slave12_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log3_ams_slave12_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log3_ams_slave12_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave12_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave12_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave12_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave12_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave12_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave12_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave12_log4_unpack(
+ struct can1__main_ft24_ams_slave12_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave12_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave12_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave12_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave12_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave12_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log4_init(struct can1__main_ft24_ams_slave12_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave12_log4_ams_slave12_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_log4_ams_slave12_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_log4_ams_slave12_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave12_log4_ams_slave12_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log4_ams_slave12_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log4_ams_slave12_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t0;
+ uint8_t ams_slave12_t1;
+ uint8_t ams_slave12_t2;
+ uint8_t ams_slave12_t3;
+ uint8_t ams_slave12_t4;
+ uint8_t ams_slave12_t5;
+ uint8_t ams_slave12_t6;
+ uint8_t ams_slave12_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave12_t0 = (uint8_t)src_p->ams_slave12_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave12_t0, 0u, 0xffu);
+ ams_slave12_t1 = (uint8_t)src_p->ams_slave12_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave12_t1, 0u, 0xffu);
+ ams_slave12_t2 = (uint8_t)src_p->ams_slave12_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave12_t2, 0u, 0xffu);
+ ams_slave12_t3 = (uint8_t)src_p->ams_slave12_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave12_t3, 0u, 0xffu);
+ ams_slave12_t4 = (uint8_t)src_p->ams_slave12_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave12_t4, 0u, 0xffu);
+ ams_slave12_t5 = (uint8_t)src_p->ams_slave12_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave12_t5, 0u, 0xffu);
+ ams_slave12_t6 = (uint8_t)src_p->ams_slave12_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave12_t6, 0u, 0xffu);
+ ams_slave12_t7 = (uint8_t)src_p->ams_slave12_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave12_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log5_unpack(
+ struct can1__main_ft24_ams_slave12_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t0;
+ uint8_t ams_slave12_t1;
+ uint8_t ams_slave12_t2;
+ uint8_t ams_slave12_t3;
+ uint8_t ams_slave12_t4;
+ uint8_t ams_slave12_t5;
+ uint8_t ams_slave12_t6;
+ uint8_t ams_slave12_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave12_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave12_t0 = (int8_t)ams_slave12_t0;
+ ams_slave12_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_t1 = (int8_t)ams_slave12_t1;
+ ams_slave12_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave12_t2 = (int8_t)ams_slave12_t2;
+ ams_slave12_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_t3 = (int8_t)ams_slave12_t3;
+ ams_slave12_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave12_t4 = (int8_t)ams_slave12_t4;
+ ams_slave12_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_t5 = (int8_t)ams_slave12_t5;
+ ams_slave12_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave12_t6 = (int8_t)ams_slave12_t6;
+ ams_slave12_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave12_t7 = (int8_t)ams_slave12_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log5_init(struct can1__main_ft24_ams_slave12_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log5_ams_slave12_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log5_ams_slave12_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log5_ams_slave12_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t10;
+ uint8_t ams_slave12_t11;
+ uint8_t ams_slave12_t12;
+ uint8_t ams_slave12_t13;
+ uint8_t ams_slave12_t14;
+ uint8_t ams_slave12_t15;
+ uint8_t ams_slave12_t8;
+ uint8_t ams_slave12_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave12_t8 = (uint8_t)src_p->ams_slave12_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave12_t8, 0u, 0xffu);
+ ams_slave12_t9 = (uint8_t)src_p->ams_slave12_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave12_t9, 0u, 0xffu);
+ ams_slave12_t10 = (uint8_t)src_p->ams_slave12_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave12_t10, 0u, 0xffu);
+ ams_slave12_t11 = (uint8_t)src_p->ams_slave12_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave12_t11, 0u, 0xffu);
+ ams_slave12_t12 = (uint8_t)src_p->ams_slave12_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave12_t12, 0u, 0xffu);
+ ams_slave12_t13 = (uint8_t)src_p->ams_slave12_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave12_t13, 0u, 0xffu);
+ ams_slave12_t14 = (uint8_t)src_p->ams_slave12_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave12_t14, 0u, 0xffu);
+ ams_slave12_t15 = (uint8_t)src_p->ams_slave12_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave12_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log6_unpack(
+ struct can1__main_ft24_ams_slave12_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t10;
+ uint8_t ams_slave12_t11;
+ uint8_t ams_slave12_t12;
+ uint8_t ams_slave12_t13;
+ uint8_t ams_slave12_t14;
+ uint8_t ams_slave12_t15;
+ uint8_t ams_slave12_t8;
+ uint8_t ams_slave12_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave12_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave12_t8 = (int8_t)ams_slave12_t8;
+ ams_slave12_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_t9 = (int8_t)ams_slave12_t9;
+ ams_slave12_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave12_t10 = (int8_t)ams_slave12_t10;
+ ams_slave12_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_t11 = (int8_t)ams_slave12_t11;
+ ams_slave12_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave12_t12 = (int8_t)ams_slave12_t12;
+ ams_slave12_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_t13 = (int8_t)ams_slave12_t13;
+ ams_slave12_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave12_t14 = (int8_t)ams_slave12_t14;
+ ams_slave12_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave12_t15 = (int8_t)ams_slave12_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log6_init(struct can1__main_ft24_ams_slave12_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log6_ams_slave12_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log6_ams_slave12_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log6_ams_slave12_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t16;
+ uint8_t ams_slave12_t17;
+ uint8_t ams_slave12_t18;
+ uint8_t ams_slave12_t19;
+ uint8_t ams_slave12_t20;
+ uint8_t ams_slave12_t21;
+ uint8_t ams_slave12_t22;
+ uint8_t ams_slave12_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave12_t16 = (uint8_t)src_p->ams_slave12_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave12_t16, 0u, 0xffu);
+ ams_slave12_t17 = (uint8_t)src_p->ams_slave12_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave12_t17, 0u, 0xffu);
+ ams_slave12_t18 = (uint8_t)src_p->ams_slave12_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave12_t18, 0u, 0xffu);
+ ams_slave12_t19 = (uint8_t)src_p->ams_slave12_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave12_t19, 0u, 0xffu);
+ ams_slave12_t20 = (uint8_t)src_p->ams_slave12_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave12_t20, 0u, 0xffu);
+ ams_slave12_t21 = (uint8_t)src_p->ams_slave12_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave12_t21, 0u, 0xffu);
+ ams_slave12_t22 = (uint8_t)src_p->ams_slave12_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave12_t22, 0u, 0xffu);
+ ams_slave12_t23 = (uint8_t)src_p->ams_slave12_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave12_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log7_unpack(
+ struct can1__main_ft24_ams_slave12_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t16;
+ uint8_t ams_slave12_t17;
+ uint8_t ams_slave12_t18;
+ uint8_t ams_slave12_t19;
+ uint8_t ams_slave12_t20;
+ uint8_t ams_slave12_t21;
+ uint8_t ams_slave12_t22;
+ uint8_t ams_slave12_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave12_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave12_t16 = (int8_t)ams_slave12_t16;
+ ams_slave12_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_t17 = (int8_t)ams_slave12_t17;
+ ams_slave12_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave12_t18 = (int8_t)ams_slave12_t18;
+ ams_slave12_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_t19 = (int8_t)ams_slave12_t19;
+ ams_slave12_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave12_t20 = (int8_t)ams_slave12_t20;
+ ams_slave12_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_t21 = (int8_t)ams_slave12_t21;
+ ams_slave12_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave12_t22 = (int8_t)ams_slave12_t22;
+ ams_slave12_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave12_t23 = (int8_t)ams_slave12_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log7_init(struct can1__main_ft24_ams_slave12_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log7_ams_slave12_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log7_ams_slave12_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log7_ams_slave12_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave12_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t24;
+ uint8_t ams_slave12_t25;
+ uint8_t ams_slave12_t26;
+ uint8_t ams_slave12_t27;
+ uint8_t ams_slave12_t28;
+ uint8_t ams_slave12_t29;
+ uint8_t ams_slave12_t30;
+ uint8_t ams_slave12_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave12_t24 = (uint8_t)src_p->ams_slave12_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave12_t24, 0u, 0xffu);
+ ams_slave12_t25 = (uint8_t)src_p->ams_slave12_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave12_t25, 0u, 0xffu);
+ ams_slave12_t26 = (uint8_t)src_p->ams_slave12_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave12_t26, 0u, 0xffu);
+ ams_slave12_t27 = (uint8_t)src_p->ams_slave12_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave12_t27, 0u, 0xffu);
+ ams_slave12_t28 = (uint8_t)src_p->ams_slave12_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave12_t28, 0u, 0xffu);
+ ams_slave12_t29 = (uint8_t)src_p->ams_slave12_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave12_t29, 0u, 0xffu);
+ ams_slave12_t30 = (uint8_t)src_p->ams_slave12_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave12_t30, 0u, 0xffu);
+ ams_slave12_t31 = (uint8_t)src_p->ams_slave12_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave12_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_log8_unpack(
+ struct can1__main_ft24_ams_slave12_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave12_t24;
+ uint8_t ams_slave12_t25;
+ uint8_t ams_slave12_t26;
+ uint8_t ams_slave12_t27;
+ uint8_t ams_slave12_t28;
+ uint8_t ams_slave12_t29;
+ uint8_t ams_slave12_t30;
+ uint8_t ams_slave12_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave12_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave12_t24 = (int8_t)ams_slave12_t24;
+ ams_slave12_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave12_t25 = (int8_t)ams_slave12_t25;
+ ams_slave12_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave12_t26 = (int8_t)ams_slave12_t26;
+ ams_slave12_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave12_t27 = (int8_t)ams_slave12_t27;
+ ams_slave12_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave12_t28 = (int8_t)ams_slave12_t28;
+ ams_slave12_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave12_t29 = (int8_t)ams_slave12_t29;
+ ams_slave12_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave12_t30 = (int8_t)ams_slave12_t30;
+ ams_slave12_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave12_t31 = (int8_t)ams_slave12_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_log8_init(struct can1__main_ft24_ams_slave12_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave12_log8_ams_slave12_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_log8_ams_slave12_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_log8_ams_slave12_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave13_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave13_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave13_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave13_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave13_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave13_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave13_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave13_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log0_unpack(
+ struct can1__main_ft24_ams_slave13_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave13_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave13_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave13_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave13_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave13_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log0_init(struct can1__main_ft24_ams_slave13_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log0_ams_slave13_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log0_ams_slave13_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log0_ams_slave13_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave13_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave13_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave13_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave13_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave13_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave13_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave13_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave13_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log1_unpack(
+ struct can1__main_ft24_ams_slave13_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave13_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave13_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave13_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave13_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave13_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log1_init(struct can1__main_ft24_ams_slave13_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log1_ams_slave13_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log1_ams_slave13_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log1_ams_slave13_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave13_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave13_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave13_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave13_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave13_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave13_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave13_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave13_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log2_unpack(
+ struct can1__main_ft24_ams_slave13_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave13_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave13_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave13_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave13_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave13_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log2_init(struct can1__main_ft24_ams_slave13_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log2_ams_slave13_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log2_ams_slave13_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log2_ams_slave13_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave13_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave13_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave13_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave13_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave13_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave13_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave13_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave13_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log3_unpack(
+ struct can1__main_ft24_ams_slave13_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave13_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave13_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave13_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave13_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave13_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log3_init(struct can1__main_ft24_ams_slave13_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave13_log3_ams_slave13_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log3_ams_slave13_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log3_ams_slave13_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave13_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave13_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave13_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave13_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave13_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave13_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave13_log4_unpack(
+ struct can1__main_ft24_ams_slave13_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave13_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave13_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave13_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave13_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave13_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log4_init(struct can1__main_ft24_ams_slave13_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave13_log4_ams_slave13_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_log4_ams_slave13_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_log4_ams_slave13_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave13_log4_ams_slave13_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log4_ams_slave13_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log4_ams_slave13_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t0;
+ uint8_t ams_slave13_t1;
+ uint8_t ams_slave13_t2;
+ uint8_t ams_slave13_t3;
+ uint8_t ams_slave13_t4;
+ uint8_t ams_slave13_t5;
+ uint8_t ams_slave13_t6;
+ uint8_t ams_slave13_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave13_t0 = (uint8_t)src_p->ams_slave13_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave13_t0, 0u, 0xffu);
+ ams_slave13_t1 = (uint8_t)src_p->ams_slave13_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave13_t1, 0u, 0xffu);
+ ams_slave13_t2 = (uint8_t)src_p->ams_slave13_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave13_t2, 0u, 0xffu);
+ ams_slave13_t3 = (uint8_t)src_p->ams_slave13_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave13_t3, 0u, 0xffu);
+ ams_slave13_t4 = (uint8_t)src_p->ams_slave13_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave13_t4, 0u, 0xffu);
+ ams_slave13_t5 = (uint8_t)src_p->ams_slave13_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave13_t5, 0u, 0xffu);
+ ams_slave13_t6 = (uint8_t)src_p->ams_slave13_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave13_t6, 0u, 0xffu);
+ ams_slave13_t7 = (uint8_t)src_p->ams_slave13_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave13_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log5_unpack(
+ struct can1__main_ft24_ams_slave13_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t0;
+ uint8_t ams_slave13_t1;
+ uint8_t ams_slave13_t2;
+ uint8_t ams_slave13_t3;
+ uint8_t ams_slave13_t4;
+ uint8_t ams_slave13_t5;
+ uint8_t ams_slave13_t6;
+ uint8_t ams_slave13_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave13_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave13_t0 = (int8_t)ams_slave13_t0;
+ ams_slave13_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_t1 = (int8_t)ams_slave13_t1;
+ ams_slave13_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave13_t2 = (int8_t)ams_slave13_t2;
+ ams_slave13_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_t3 = (int8_t)ams_slave13_t3;
+ ams_slave13_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave13_t4 = (int8_t)ams_slave13_t4;
+ ams_slave13_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_t5 = (int8_t)ams_slave13_t5;
+ ams_slave13_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave13_t6 = (int8_t)ams_slave13_t6;
+ ams_slave13_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave13_t7 = (int8_t)ams_slave13_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log5_init(struct can1__main_ft24_ams_slave13_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log5_ams_slave13_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log5_ams_slave13_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log5_ams_slave13_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t10;
+ uint8_t ams_slave13_t11;
+ uint8_t ams_slave13_t12;
+ uint8_t ams_slave13_t13;
+ uint8_t ams_slave13_t14;
+ uint8_t ams_slave13_t15;
+ uint8_t ams_slave13_t8;
+ uint8_t ams_slave13_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave13_t8 = (uint8_t)src_p->ams_slave13_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave13_t8, 0u, 0xffu);
+ ams_slave13_t9 = (uint8_t)src_p->ams_slave13_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave13_t9, 0u, 0xffu);
+ ams_slave13_t10 = (uint8_t)src_p->ams_slave13_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave13_t10, 0u, 0xffu);
+ ams_slave13_t11 = (uint8_t)src_p->ams_slave13_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave13_t11, 0u, 0xffu);
+ ams_slave13_t12 = (uint8_t)src_p->ams_slave13_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave13_t12, 0u, 0xffu);
+ ams_slave13_t13 = (uint8_t)src_p->ams_slave13_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave13_t13, 0u, 0xffu);
+ ams_slave13_t14 = (uint8_t)src_p->ams_slave13_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave13_t14, 0u, 0xffu);
+ ams_slave13_t15 = (uint8_t)src_p->ams_slave13_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave13_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log6_unpack(
+ struct can1__main_ft24_ams_slave13_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t10;
+ uint8_t ams_slave13_t11;
+ uint8_t ams_slave13_t12;
+ uint8_t ams_slave13_t13;
+ uint8_t ams_slave13_t14;
+ uint8_t ams_slave13_t15;
+ uint8_t ams_slave13_t8;
+ uint8_t ams_slave13_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave13_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave13_t8 = (int8_t)ams_slave13_t8;
+ ams_slave13_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_t9 = (int8_t)ams_slave13_t9;
+ ams_slave13_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave13_t10 = (int8_t)ams_slave13_t10;
+ ams_slave13_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_t11 = (int8_t)ams_slave13_t11;
+ ams_slave13_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave13_t12 = (int8_t)ams_slave13_t12;
+ ams_slave13_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_t13 = (int8_t)ams_slave13_t13;
+ ams_slave13_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave13_t14 = (int8_t)ams_slave13_t14;
+ ams_slave13_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave13_t15 = (int8_t)ams_slave13_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log6_init(struct can1__main_ft24_ams_slave13_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log6_ams_slave13_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log6_ams_slave13_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log6_ams_slave13_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t16;
+ uint8_t ams_slave13_t17;
+ uint8_t ams_slave13_t18;
+ uint8_t ams_slave13_t19;
+ uint8_t ams_slave13_t20;
+ uint8_t ams_slave13_t21;
+ uint8_t ams_slave13_t22;
+ uint8_t ams_slave13_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave13_t16 = (uint8_t)src_p->ams_slave13_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave13_t16, 0u, 0xffu);
+ ams_slave13_t17 = (uint8_t)src_p->ams_slave13_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave13_t17, 0u, 0xffu);
+ ams_slave13_t18 = (uint8_t)src_p->ams_slave13_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave13_t18, 0u, 0xffu);
+ ams_slave13_t19 = (uint8_t)src_p->ams_slave13_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave13_t19, 0u, 0xffu);
+ ams_slave13_t20 = (uint8_t)src_p->ams_slave13_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave13_t20, 0u, 0xffu);
+ ams_slave13_t21 = (uint8_t)src_p->ams_slave13_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave13_t21, 0u, 0xffu);
+ ams_slave13_t22 = (uint8_t)src_p->ams_slave13_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave13_t22, 0u, 0xffu);
+ ams_slave13_t23 = (uint8_t)src_p->ams_slave13_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave13_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log7_unpack(
+ struct can1__main_ft24_ams_slave13_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t16;
+ uint8_t ams_slave13_t17;
+ uint8_t ams_slave13_t18;
+ uint8_t ams_slave13_t19;
+ uint8_t ams_slave13_t20;
+ uint8_t ams_slave13_t21;
+ uint8_t ams_slave13_t22;
+ uint8_t ams_slave13_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave13_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave13_t16 = (int8_t)ams_slave13_t16;
+ ams_slave13_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_t17 = (int8_t)ams_slave13_t17;
+ ams_slave13_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave13_t18 = (int8_t)ams_slave13_t18;
+ ams_slave13_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_t19 = (int8_t)ams_slave13_t19;
+ ams_slave13_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave13_t20 = (int8_t)ams_slave13_t20;
+ ams_slave13_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_t21 = (int8_t)ams_slave13_t21;
+ ams_slave13_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave13_t22 = (int8_t)ams_slave13_t22;
+ ams_slave13_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave13_t23 = (int8_t)ams_slave13_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log7_init(struct can1__main_ft24_ams_slave13_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log7_ams_slave13_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log7_ams_slave13_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log7_ams_slave13_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave13_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t24;
+ uint8_t ams_slave13_t25;
+ uint8_t ams_slave13_t26;
+ uint8_t ams_slave13_t27;
+ uint8_t ams_slave13_t28;
+ uint8_t ams_slave13_t29;
+ uint8_t ams_slave13_t30;
+ uint8_t ams_slave13_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave13_t24 = (uint8_t)src_p->ams_slave13_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave13_t24, 0u, 0xffu);
+ ams_slave13_t25 = (uint8_t)src_p->ams_slave13_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave13_t25, 0u, 0xffu);
+ ams_slave13_t26 = (uint8_t)src_p->ams_slave13_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave13_t26, 0u, 0xffu);
+ ams_slave13_t27 = (uint8_t)src_p->ams_slave13_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave13_t27, 0u, 0xffu);
+ ams_slave13_t28 = (uint8_t)src_p->ams_slave13_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave13_t28, 0u, 0xffu);
+ ams_slave13_t29 = (uint8_t)src_p->ams_slave13_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave13_t29, 0u, 0xffu);
+ ams_slave13_t30 = (uint8_t)src_p->ams_slave13_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave13_t30, 0u, 0xffu);
+ ams_slave13_t31 = (uint8_t)src_p->ams_slave13_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave13_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_log8_unpack(
+ struct can1__main_ft24_ams_slave13_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave13_t24;
+ uint8_t ams_slave13_t25;
+ uint8_t ams_slave13_t26;
+ uint8_t ams_slave13_t27;
+ uint8_t ams_slave13_t28;
+ uint8_t ams_slave13_t29;
+ uint8_t ams_slave13_t30;
+ uint8_t ams_slave13_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave13_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave13_t24 = (int8_t)ams_slave13_t24;
+ ams_slave13_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave13_t25 = (int8_t)ams_slave13_t25;
+ ams_slave13_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave13_t26 = (int8_t)ams_slave13_t26;
+ ams_slave13_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave13_t27 = (int8_t)ams_slave13_t27;
+ ams_slave13_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave13_t28 = (int8_t)ams_slave13_t28;
+ ams_slave13_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave13_t29 = (int8_t)ams_slave13_t29;
+ ams_slave13_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave13_t30 = (int8_t)ams_slave13_t30;
+ ams_slave13_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave13_t31 = (int8_t)ams_slave13_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_log8_init(struct can1__main_ft24_ams_slave13_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave13_log8_ams_slave13_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_log8_ams_slave13_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_log8_ams_slave13_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave14_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave14_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave14_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave14_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave14_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave14_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave14_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave14_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log0_unpack(
+ struct can1__main_ft24_ams_slave14_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave14_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave14_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave14_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave14_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave14_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log0_init(struct can1__main_ft24_ams_slave14_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log0_ams_slave14_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log0_ams_slave14_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log0_ams_slave14_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave14_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave14_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave14_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave14_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave14_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave14_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave14_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave14_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log1_unpack(
+ struct can1__main_ft24_ams_slave14_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave14_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave14_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave14_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave14_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave14_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log1_init(struct can1__main_ft24_ams_slave14_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log1_ams_slave14_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log1_ams_slave14_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log1_ams_slave14_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave14_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave14_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave14_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave14_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave14_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave14_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave14_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave14_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log2_unpack(
+ struct can1__main_ft24_ams_slave14_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave14_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave14_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave14_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave14_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave14_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log2_init(struct can1__main_ft24_ams_slave14_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log2_ams_slave14_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log2_ams_slave14_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log2_ams_slave14_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave14_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave14_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave14_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave14_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave14_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave14_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave14_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave14_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log3_unpack(
+ struct can1__main_ft24_ams_slave14_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave14_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave14_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave14_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave14_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave14_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log3_init(struct can1__main_ft24_ams_slave14_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave14_log3_ams_slave14_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log3_ams_slave14_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log3_ams_slave14_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave14_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave14_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave14_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave14_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave14_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave14_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave14_log4_unpack(
+ struct can1__main_ft24_ams_slave14_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave14_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave14_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave14_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave14_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave14_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log4_init(struct can1__main_ft24_ams_slave14_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave14_log4_ams_slave14_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_log4_ams_slave14_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_log4_ams_slave14_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave14_log4_ams_slave14_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log4_ams_slave14_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log4_ams_slave14_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t0;
+ uint8_t ams_slave14_t1;
+ uint8_t ams_slave14_t2;
+ uint8_t ams_slave14_t3;
+ uint8_t ams_slave14_t4;
+ uint8_t ams_slave14_t5;
+ uint8_t ams_slave14_t6;
+ uint8_t ams_slave14_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave14_t0 = (uint8_t)src_p->ams_slave14_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave14_t0, 0u, 0xffu);
+ ams_slave14_t1 = (uint8_t)src_p->ams_slave14_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave14_t1, 0u, 0xffu);
+ ams_slave14_t2 = (uint8_t)src_p->ams_slave14_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave14_t2, 0u, 0xffu);
+ ams_slave14_t3 = (uint8_t)src_p->ams_slave14_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave14_t3, 0u, 0xffu);
+ ams_slave14_t4 = (uint8_t)src_p->ams_slave14_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave14_t4, 0u, 0xffu);
+ ams_slave14_t5 = (uint8_t)src_p->ams_slave14_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave14_t5, 0u, 0xffu);
+ ams_slave14_t6 = (uint8_t)src_p->ams_slave14_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave14_t6, 0u, 0xffu);
+ ams_slave14_t7 = (uint8_t)src_p->ams_slave14_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave14_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log5_unpack(
+ struct can1__main_ft24_ams_slave14_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t0;
+ uint8_t ams_slave14_t1;
+ uint8_t ams_slave14_t2;
+ uint8_t ams_slave14_t3;
+ uint8_t ams_slave14_t4;
+ uint8_t ams_slave14_t5;
+ uint8_t ams_slave14_t6;
+ uint8_t ams_slave14_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave14_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave14_t0 = (int8_t)ams_slave14_t0;
+ ams_slave14_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_t1 = (int8_t)ams_slave14_t1;
+ ams_slave14_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave14_t2 = (int8_t)ams_slave14_t2;
+ ams_slave14_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_t3 = (int8_t)ams_slave14_t3;
+ ams_slave14_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave14_t4 = (int8_t)ams_slave14_t4;
+ ams_slave14_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_t5 = (int8_t)ams_slave14_t5;
+ ams_slave14_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave14_t6 = (int8_t)ams_slave14_t6;
+ ams_slave14_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave14_t7 = (int8_t)ams_slave14_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log5_init(struct can1__main_ft24_ams_slave14_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log5_ams_slave14_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log5_ams_slave14_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log5_ams_slave14_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t10;
+ uint8_t ams_slave14_t11;
+ uint8_t ams_slave14_t12;
+ uint8_t ams_slave14_t13;
+ uint8_t ams_slave14_t14;
+ uint8_t ams_slave14_t15;
+ uint8_t ams_slave14_t8;
+ uint8_t ams_slave14_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave14_t8 = (uint8_t)src_p->ams_slave14_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave14_t8, 0u, 0xffu);
+ ams_slave14_t9 = (uint8_t)src_p->ams_slave14_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave14_t9, 0u, 0xffu);
+ ams_slave14_t10 = (uint8_t)src_p->ams_slave14_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave14_t10, 0u, 0xffu);
+ ams_slave14_t11 = (uint8_t)src_p->ams_slave14_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave14_t11, 0u, 0xffu);
+ ams_slave14_t12 = (uint8_t)src_p->ams_slave14_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave14_t12, 0u, 0xffu);
+ ams_slave14_t13 = (uint8_t)src_p->ams_slave14_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave14_t13, 0u, 0xffu);
+ ams_slave14_t14 = (uint8_t)src_p->ams_slave14_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave14_t14, 0u, 0xffu);
+ ams_slave14_t15 = (uint8_t)src_p->ams_slave14_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave14_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log6_unpack(
+ struct can1__main_ft24_ams_slave14_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t10;
+ uint8_t ams_slave14_t11;
+ uint8_t ams_slave14_t12;
+ uint8_t ams_slave14_t13;
+ uint8_t ams_slave14_t14;
+ uint8_t ams_slave14_t15;
+ uint8_t ams_slave14_t8;
+ uint8_t ams_slave14_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave14_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave14_t8 = (int8_t)ams_slave14_t8;
+ ams_slave14_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_t9 = (int8_t)ams_slave14_t9;
+ ams_slave14_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave14_t10 = (int8_t)ams_slave14_t10;
+ ams_slave14_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_t11 = (int8_t)ams_slave14_t11;
+ ams_slave14_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave14_t12 = (int8_t)ams_slave14_t12;
+ ams_slave14_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_t13 = (int8_t)ams_slave14_t13;
+ ams_slave14_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave14_t14 = (int8_t)ams_slave14_t14;
+ ams_slave14_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave14_t15 = (int8_t)ams_slave14_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log6_init(struct can1__main_ft24_ams_slave14_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log6_ams_slave14_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log6_ams_slave14_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log6_ams_slave14_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t16;
+ uint8_t ams_slave14_t17;
+ uint8_t ams_slave14_t18;
+ uint8_t ams_slave14_t19;
+ uint8_t ams_slave14_t20;
+ uint8_t ams_slave14_t21;
+ uint8_t ams_slave14_t22;
+ uint8_t ams_slave14_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave14_t16 = (uint8_t)src_p->ams_slave14_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave14_t16, 0u, 0xffu);
+ ams_slave14_t17 = (uint8_t)src_p->ams_slave14_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave14_t17, 0u, 0xffu);
+ ams_slave14_t18 = (uint8_t)src_p->ams_slave14_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave14_t18, 0u, 0xffu);
+ ams_slave14_t19 = (uint8_t)src_p->ams_slave14_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave14_t19, 0u, 0xffu);
+ ams_slave14_t20 = (uint8_t)src_p->ams_slave14_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave14_t20, 0u, 0xffu);
+ ams_slave14_t21 = (uint8_t)src_p->ams_slave14_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave14_t21, 0u, 0xffu);
+ ams_slave14_t22 = (uint8_t)src_p->ams_slave14_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave14_t22, 0u, 0xffu);
+ ams_slave14_t23 = (uint8_t)src_p->ams_slave14_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave14_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log7_unpack(
+ struct can1__main_ft24_ams_slave14_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t16;
+ uint8_t ams_slave14_t17;
+ uint8_t ams_slave14_t18;
+ uint8_t ams_slave14_t19;
+ uint8_t ams_slave14_t20;
+ uint8_t ams_slave14_t21;
+ uint8_t ams_slave14_t22;
+ uint8_t ams_slave14_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave14_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave14_t16 = (int8_t)ams_slave14_t16;
+ ams_slave14_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_t17 = (int8_t)ams_slave14_t17;
+ ams_slave14_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave14_t18 = (int8_t)ams_slave14_t18;
+ ams_slave14_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_t19 = (int8_t)ams_slave14_t19;
+ ams_slave14_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave14_t20 = (int8_t)ams_slave14_t20;
+ ams_slave14_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_t21 = (int8_t)ams_slave14_t21;
+ ams_slave14_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave14_t22 = (int8_t)ams_slave14_t22;
+ ams_slave14_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave14_t23 = (int8_t)ams_slave14_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log7_init(struct can1__main_ft24_ams_slave14_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log7_ams_slave14_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log7_ams_slave14_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log7_ams_slave14_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave14_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t24;
+ uint8_t ams_slave14_t25;
+ uint8_t ams_slave14_t26;
+ uint8_t ams_slave14_t27;
+ uint8_t ams_slave14_t28;
+ uint8_t ams_slave14_t29;
+ uint8_t ams_slave14_t30;
+ uint8_t ams_slave14_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave14_t24 = (uint8_t)src_p->ams_slave14_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave14_t24, 0u, 0xffu);
+ ams_slave14_t25 = (uint8_t)src_p->ams_slave14_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave14_t25, 0u, 0xffu);
+ ams_slave14_t26 = (uint8_t)src_p->ams_slave14_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave14_t26, 0u, 0xffu);
+ ams_slave14_t27 = (uint8_t)src_p->ams_slave14_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave14_t27, 0u, 0xffu);
+ ams_slave14_t28 = (uint8_t)src_p->ams_slave14_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave14_t28, 0u, 0xffu);
+ ams_slave14_t29 = (uint8_t)src_p->ams_slave14_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave14_t29, 0u, 0xffu);
+ ams_slave14_t30 = (uint8_t)src_p->ams_slave14_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave14_t30, 0u, 0xffu);
+ ams_slave14_t31 = (uint8_t)src_p->ams_slave14_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave14_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_log8_unpack(
+ struct can1__main_ft24_ams_slave14_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave14_t24;
+ uint8_t ams_slave14_t25;
+ uint8_t ams_slave14_t26;
+ uint8_t ams_slave14_t27;
+ uint8_t ams_slave14_t28;
+ uint8_t ams_slave14_t29;
+ uint8_t ams_slave14_t30;
+ uint8_t ams_slave14_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave14_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave14_t24 = (int8_t)ams_slave14_t24;
+ ams_slave14_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave14_t25 = (int8_t)ams_slave14_t25;
+ ams_slave14_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave14_t26 = (int8_t)ams_slave14_t26;
+ ams_slave14_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave14_t27 = (int8_t)ams_slave14_t27;
+ ams_slave14_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave14_t28 = (int8_t)ams_slave14_t28;
+ ams_slave14_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave14_t29 = (int8_t)ams_slave14_t29;
+ ams_slave14_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave14_t30 = (int8_t)ams_slave14_t30;
+ ams_slave14_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave14_t31 = (int8_t)ams_slave14_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_log8_init(struct can1__main_ft24_ams_slave14_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave14_log8_ams_slave14_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_log8_ams_slave14_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_log8_ams_slave14_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log0_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log0_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave15_v0, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave15_v0, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave15_v1, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave15_v1, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave15_v2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave15_v2, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave15_v3, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave15_v3, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log0_unpack(
+ struct can1__main_ft24_ams_slave15_log0_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave15_v0 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave15_v0 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_v1 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave15_v1 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_v2 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave15_v2 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_v3 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave15_v3 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log0_init(struct can1__main_ft24_ams_slave15_log0_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log0_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v0_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v0_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v0_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v1_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v1_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v1_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v2_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v2_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v2_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log0_ams_slave15_v3_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log0_ams_slave15_v3_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log0_ams_slave15_v3_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave15_v4, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave15_v4, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave15_v5, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave15_v5, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave15_v6, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave15_v6, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave15_v7, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave15_v7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log1_unpack(
+ struct can1__main_ft24_ams_slave15_log1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave15_v4 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave15_v4 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_v5 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave15_v5 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_v6 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave15_v6 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_v7 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave15_v7 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log1_init(struct can1__main_ft24_ams_slave15_log1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v4_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v4_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v4_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v5_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v5_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v5_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v6_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v6_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v6_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log1_ams_slave15_v7_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log1_ams_slave15_v7_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log1_ams_slave15_v7_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave15_v8, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave15_v8, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave15_v9, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave15_v9, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave15_v10, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave15_v10, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave15_v11, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave15_v11, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log2_unpack(
+ struct can1__main_ft24_ams_slave15_log2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave15_v8 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave15_v8 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_v9 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave15_v9 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_v10 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave15_v10 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_v11 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave15_v11 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log2_init(struct can1__main_ft24_ams_slave15_log2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v8_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v8_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v8_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v9_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v9_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v9_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v10_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v10_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v10_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log2_ams_slave15_v11_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log2_ams_slave15_v11_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log2_ams_slave15_v11_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave15_v12, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave15_v12, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave15_v13, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave15_v13, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave15_v14, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave15_v14, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->ams_slave15_v15, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->ams_slave15_v15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log3_unpack(
+ struct can1__main_ft24_ams_slave15_log3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave15_v12 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave15_v12 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_v13 = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave15_v13 |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_v14 = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave15_v14 |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_v15 = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->ams_slave15_v15 |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log3_init(struct can1__main_ft24_ams_slave15_log3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v12_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v12_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v12_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v13_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v13_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v13_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v14_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v14_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v14_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_ams_slave15_log3_ams_slave15_v15_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log3_ams_slave15_v15_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log3_ams_slave15_v15_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log4_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->ams_slave15_v16, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->ams_slave15_v16, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave15_failed_sensors, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave15_failed_sensors, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave15_failed_sensors, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave15_failed_sensors, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_slave15_log4_unpack(
+ struct can1__main_ft24_ams_slave15_log4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave15_v16 = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->ams_slave15_v16 |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_failed_sensors = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave15_failed_sensors |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave15_failed_sensors |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave15_failed_sensors |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log4_init(struct can1__main_ft24_ams_slave15_log4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_ams_slave15_log4_ams_slave15_v16_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_log4_ams_slave15_v16_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_log4_ams_slave15_v16_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave15_log4_ams_slave15_failed_sensors_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log4_ams_slave15_failed_sensors_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log4_ams_slave15_failed_sensors_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log5_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log5_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t0;
+ uint8_t ams_slave15_t1;
+ uint8_t ams_slave15_t2;
+ uint8_t ams_slave15_t3;
+ uint8_t ams_slave15_t4;
+ uint8_t ams_slave15_t5;
+ uint8_t ams_slave15_t6;
+ uint8_t ams_slave15_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave15_t0 = (uint8_t)src_p->ams_slave15_t0;
+ dst_p[0] |= pack_left_shift_u8(ams_slave15_t0, 0u, 0xffu);
+ ams_slave15_t1 = (uint8_t)src_p->ams_slave15_t1;
+ dst_p[1] |= pack_left_shift_u8(ams_slave15_t1, 0u, 0xffu);
+ ams_slave15_t2 = (uint8_t)src_p->ams_slave15_t2;
+ dst_p[2] |= pack_left_shift_u8(ams_slave15_t2, 0u, 0xffu);
+ ams_slave15_t3 = (uint8_t)src_p->ams_slave15_t3;
+ dst_p[3] |= pack_left_shift_u8(ams_slave15_t3, 0u, 0xffu);
+ ams_slave15_t4 = (uint8_t)src_p->ams_slave15_t4;
+ dst_p[4] |= pack_left_shift_u8(ams_slave15_t4, 0u, 0xffu);
+ ams_slave15_t5 = (uint8_t)src_p->ams_slave15_t5;
+ dst_p[5] |= pack_left_shift_u8(ams_slave15_t5, 0u, 0xffu);
+ ams_slave15_t6 = (uint8_t)src_p->ams_slave15_t6;
+ dst_p[6] |= pack_left_shift_u8(ams_slave15_t6, 0u, 0xffu);
+ ams_slave15_t7 = (uint8_t)src_p->ams_slave15_t7;
+ dst_p[7] |= pack_left_shift_u8(ams_slave15_t7, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log5_unpack(
+ struct can1__main_ft24_ams_slave15_log5_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t0;
+ uint8_t ams_slave15_t1;
+ uint8_t ams_slave15_t2;
+ uint8_t ams_slave15_t3;
+ uint8_t ams_slave15_t4;
+ uint8_t ams_slave15_t5;
+ uint8_t ams_slave15_t6;
+ uint8_t ams_slave15_t7;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave15_t0 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave15_t0 = (int8_t)ams_slave15_t0;
+ ams_slave15_t1 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_t1 = (int8_t)ams_slave15_t1;
+ ams_slave15_t2 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave15_t2 = (int8_t)ams_slave15_t2;
+ ams_slave15_t3 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_t3 = (int8_t)ams_slave15_t3;
+ ams_slave15_t4 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave15_t4 = (int8_t)ams_slave15_t4;
+ ams_slave15_t5 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_t5 = (int8_t)ams_slave15_t5;
+ ams_slave15_t6 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave15_t6 = (int8_t)ams_slave15_t6;
+ ams_slave15_t7 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave15_t7 = (int8_t)ams_slave15_t7;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log5_init(struct can1__main_ft24_ams_slave15_log5_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log5_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t0_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t0_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t0_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t1_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t1_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t1_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t2_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t2_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t2_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t3_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t3_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t3_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t4_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t4_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t4_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t5_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t5_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t5_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t6_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t6_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t6_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log5_ams_slave15_t7_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log5_ams_slave15_t7_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log5_ams_slave15_t7_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log6_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log6_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t10;
+ uint8_t ams_slave15_t11;
+ uint8_t ams_slave15_t12;
+ uint8_t ams_slave15_t13;
+ uint8_t ams_slave15_t14;
+ uint8_t ams_slave15_t15;
+ uint8_t ams_slave15_t8;
+ uint8_t ams_slave15_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave15_t8 = (uint8_t)src_p->ams_slave15_t8;
+ dst_p[0] |= pack_left_shift_u8(ams_slave15_t8, 0u, 0xffu);
+ ams_slave15_t9 = (uint8_t)src_p->ams_slave15_t9;
+ dst_p[1] |= pack_left_shift_u8(ams_slave15_t9, 0u, 0xffu);
+ ams_slave15_t10 = (uint8_t)src_p->ams_slave15_t10;
+ dst_p[2] |= pack_left_shift_u8(ams_slave15_t10, 0u, 0xffu);
+ ams_slave15_t11 = (uint8_t)src_p->ams_slave15_t11;
+ dst_p[3] |= pack_left_shift_u8(ams_slave15_t11, 0u, 0xffu);
+ ams_slave15_t12 = (uint8_t)src_p->ams_slave15_t12;
+ dst_p[4] |= pack_left_shift_u8(ams_slave15_t12, 0u, 0xffu);
+ ams_slave15_t13 = (uint8_t)src_p->ams_slave15_t13;
+ dst_p[5] |= pack_left_shift_u8(ams_slave15_t13, 0u, 0xffu);
+ ams_slave15_t14 = (uint8_t)src_p->ams_slave15_t14;
+ dst_p[6] |= pack_left_shift_u8(ams_slave15_t14, 0u, 0xffu);
+ ams_slave15_t15 = (uint8_t)src_p->ams_slave15_t15;
+ dst_p[7] |= pack_left_shift_u8(ams_slave15_t15, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log6_unpack(
+ struct can1__main_ft24_ams_slave15_log6_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t10;
+ uint8_t ams_slave15_t11;
+ uint8_t ams_slave15_t12;
+ uint8_t ams_slave15_t13;
+ uint8_t ams_slave15_t14;
+ uint8_t ams_slave15_t15;
+ uint8_t ams_slave15_t8;
+ uint8_t ams_slave15_t9;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave15_t8 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave15_t8 = (int8_t)ams_slave15_t8;
+ ams_slave15_t9 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_t9 = (int8_t)ams_slave15_t9;
+ ams_slave15_t10 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave15_t10 = (int8_t)ams_slave15_t10;
+ ams_slave15_t11 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_t11 = (int8_t)ams_slave15_t11;
+ ams_slave15_t12 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave15_t12 = (int8_t)ams_slave15_t12;
+ ams_slave15_t13 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_t13 = (int8_t)ams_slave15_t13;
+ ams_slave15_t14 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave15_t14 = (int8_t)ams_slave15_t14;
+ ams_slave15_t15 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave15_t15 = (int8_t)ams_slave15_t15;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log6_init(struct can1__main_ft24_ams_slave15_log6_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log6_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t8_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t8_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t8_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t9_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t9_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t9_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t10_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t10_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t10_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t11_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t11_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t11_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t12_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t12_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t12_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t13_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t13_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t13_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t14_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t14_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t14_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log6_ams_slave15_t15_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log6_ams_slave15_t15_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log6_ams_slave15_t15_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log7_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log7_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t16;
+ uint8_t ams_slave15_t17;
+ uint8_t ams_slave15_t18;
+ uint8_t ams_slave15_t19;
+ uint8_t ams_slave15_t20;
+ uint8_t ams_slave15_t21;
+ uint8_t ams_slave15_t22;
+ uint8_t ams_slave15_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave15_t16 = (uint8_t)src_p->ams_slave15_t16;
+ dst_p[0] |= pack_left_shift_u8(ams_slave15_t16, 0u, 0xffu);
+ ams_slave15_t17 = (uint8_t)src_p->ams_slave15_t17;
+ dst_p[1] |= pack_left_shift_u8(ams_slave15_t17, 0u, 0xffu);
+ ams_slave15_t18 = (uint8_t)src_p->ams_slave15_t18;
+ dst_p[2] |= pack_left_shift_u8(ams_slave15_t18, 0u, 0xffu);
+ ams_slave15_t19 = (uint8_t)src_p->ams_slave15_t19;
+ dst_p[3] |= pack_left_shift_u8(ams_slave15_t19, 0u, 0xffu);
+ ams_slave15_t20 = (uint8_t)src_p->ams_slave15_t20;
+ dst_p[4] |= pack_left_shift_u8(ams_slave15_t20, 0u, 0xffu);
+ ams_slave15_t21 = (uint8_t)src_p->ams_slave15_t21;
+ dst_p[5] |= pack_left_shift_u8(ams_slave15_t21, 0u, 0xffu);
+ ams_slave15_t22 = (uint8_t)src_p->ams_slave15_t22;
+ dst_p[6] |= pack_left_shift_u8(ams_slave15_t22, 0u, 0xffu);
+ ams_slave15_t23 = (uint8_t)src_p->ams_slave15_t23;
+ dst_p[7] |= pack_left_shift_u8(ams_slave15_t23, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log7_unpack(
+ struct can1__main_ft24_ams_slave15_log7_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t16;
+ uint8_t ams_slave15_t17;
+ uint8_t ams_slave15_t18;
+ uint8_t ams_slave15_t19;
+ uint8_t ams_slave15_t20;
+ uint8_t ams_slave15_t21;
+ uint8_t ams_slave15_t22;
+ uint8_t ams_slave15_t23;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave15_t16 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave15_t16 = (int8_t)ams_slave15_t16;
+ ams_slave15_t17 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_t17 = (int8_t)ams_slave15_t17;
+ ams_slave15_t18 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave15_t18 = (int8_t)ams_slave15_t18;
+ ams_slave15_t19 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_t19 = (int8_t)ams_slave15_t19;
+ ams_slave15_t20 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave15_t20 = (int8_t)ams_slave15_t20;
+ ams_slave15_t21 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_t21 = (int8_t)ams_slave15_t21;
+ ams_slave15_t22 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave15_t22 = (int8_t)ams_slave15_t22;
+ ams_slave15_t23 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave15_t23 = (int8_t)ams_slave15_t23;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log7_init(struct can1__main_ft24_ams_slave15_log7_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log7_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t16_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t16_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t16_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t17_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t17_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t17_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t18_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t18_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t18_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t19_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t19_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t19_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t20_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t20_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t20_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t21_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t21_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t21_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t22_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t22_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t22_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log7_ams_slave15_t23_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log7_ams_slave15_t23_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log7_ams_slave15_t23_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave15_log8_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_log8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t24;
+ uint8_t ams_slave15_t25;
+ uint8_t ams_slave15_t26;
+ uint8_t ams_slave15_t27;
+ uint8_t ams_slave15_t28;
+ uint8_t ams_slave15_t29;
+ uint8_t ams_slave15_t30;
+ uint8_t ams_slave15_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ ams_slave15_t24 = (uint8_t)src_p->ams_slave15_t24;
+ dst_p[0] |= pack_left_shift_u8(ams_slave15_t24, 0u, 0xffu);
+ ams_slave15_t25 = (uint8_t)src_p->ams_slave15_t25;
+ dst_p[1] |= pack_left_shift_u8(ams_slave15_t25, 0u, 0xffu);
+ ams_slave15_t26 = (uint8_t)src_p->ams_slave15_t26;
+ dst_p[2] |= pack_left_shift_u8(ams_slave15_t26, 0u, 0xffu);
+ ams_slave15_t27 = (uint8_t)src_p->ams_slave15_t27;
+ dst_p[3] |= pack_left_shift_u8(ams_slave15_t27, 0u, 0xffu);
+ ams_slave15_t28 = (uint8_t)src_p->ams_slave15_t28;
+ dst_p[4] |= pack_left_shift_u8(ams_slave15_t28, 0u, 0xffu);
+ ams_slave15_t29 = (uint8_t)src_p->ams_slave15_t29;
+ dst_p[5] |= pack_left_shift_u8(ams_slave15_t29, 0u, 0xffu);
+ ams_slave15_t30 = (uint8_t)src_p->ams_slave15_t30;
+ dst_p[6] |= pack_left_shift_u8(ams_slave15_t30, 0u, 0xffu);
+ ams_slave15_t31 = (uint8_t)src_p->ams_slave15_t31;
+ dst_p[7] |= pack_left_shift_u8(ams_slave15_t31, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_log8_unpack(
+ struct can1__main_ft24_ams_slave15_log8_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_slave15_t24;
+ uint8_t ams_slave15_t25;
+ uint8_t ams_slave15_t26;
+ uint8_t ams_slave15_t27;
+ uint8_t ams_slave15_t28;
+ uint8_t ams_slave15_t29;
+ uint8_t ams_slave15_t30;
+ uint8_t ams_slave15_t31;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ ams_slave15_t24 = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave15_t24 = (int8_t)ams_slave15_t24;
+ ams_slave15_t25 = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave15_t25 = (int8_t)ams_slave15_t25;
+ ams_slave15_t26 = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->ams_slave15_t26 = (int8_t)ams_slave15_t26;
+ ams_slave15_t27 = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave15_t27 = (int8_t)ams_slave15_t27;
+ ams_slave15_t28 = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->ams_slave15_t28 = (int8_t)ams_slave15_t28;
+ ams_slave15_t29 = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->ams_slave15_t29 = (int8_t)ams_slave15_t29;
+ ams_slave15_t30 = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->ams_slave15_t30 = (int8_t)ams_slave15_t30;
+ ams_slave15_t31 = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+ dst_p->ams_slave15_t31 = (int8_t)ams_slave15_t31;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_log8_init(struct can1__main_ft24_ams_slave15_log8_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_log8_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t24_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t24_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t24_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t25_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t25_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t25_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t26_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t26_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t26_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t27_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t27_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t27_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t28_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t28_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t28_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t29_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t29_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t29_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t30_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t30_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t30_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_slave15_log8_ams_slave15_t31_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_log8_ams_slave15_t31_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_log8_ams_slave15_t31_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_jetson_rx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_jetson_rx_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 4);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_as_mission, 0u, 0x07u);
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_as_state, 3u, 0x38u);
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_power_off, 6u, 0x40u);
+ dst_p[0] |= pack_left_shift_u8(src_p->jetson_reset, 7u, 0x80u);
+ dst_p[1] |= pack_left_shift_u8(src_p->jetson_speed, 0u, 0xffu);
+ dst_p[2] |= pack_left_shift_u8(src_p->jetson_speed_x_sens, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->jetson_allow_torque, 0u, 0x01u);
+
+ return (4);
+}
+
+int can1__main_ft24_jetson_rx_unpack(
+ struct can1__main_ft24_jetson_rx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ dst_p->jetson_as_mission = unpack_right_shift_u8(src_p[0], 0u, 0x07u);
+ dst_p->jetson_as_state = unpack_right_shift_u8(src_p[0], 3u, 0x38u);
+ dst_p->jetson_power_off = unpack_right_shift_u8(src_p[0], 6u, 0x40u);
+ dst_p->jetson_reset = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->jetson_speed = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->jetson_speed_x_sens = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->jetson_allow_torque = unpack_right_shift_u8(src_p[3], 0u, 0x01u);
+
+ return (0);
+}
+
+int can1__main_ft24_jetson_rx_init(struct can1__main_ft24_jetson_rx_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_jetson_rx_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_as_mission_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_rx_jetson_as_mission_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_as_mission_is_in_range(uint8_t value)
+{
+ return (value <= 7u);
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_as_state_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_rx_jetson_as_state_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_as_state_is_in_range(uint8_t value)
+{
+ return (value <= 5u);
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_power_off_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_rx_jetson_power_off_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_power_off_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_reset_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_rx_jetson_reset_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_reset_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_speed_encode(double value)
+{
+ return (uint8_t)(value / 0.2);
+}
+
+double can1__main_ft24_jetson_rx_jetson_speed_decode(uint8_t value)
+{
+ return ((double)value * 0.2);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_speed_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_speed_x_sens_encode(double value)
+{
+ return (uint8_t)(value / 0.2);
+}
+
+double can1__main_ft24_jetson_rx_jetson_speed_x_sens_decode(uint8_t value)
+{
+ return ((double)value * 0.2);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_speed_x_sens_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_jetson_rx_jetson_allow_torque_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_jetson_rx_jetson_allow_torque_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_jetson_rx_jetson_allow_torque_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+int can1__main_ft24_ams_slave15_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave15_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave15_status_unpack(
+ struct can1__main_ft24_ams_slave15_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave15_status_init(struct can1__main_ft24_ams_slave15_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave15_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave15_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave15_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave15_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave15_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave15_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave15_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave15_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave15_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave15_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave15_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave14_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave14_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave14_status_unpack(
+ struct can1__main_ft24_ams_slave14_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave14_status_init(struct can1__main_ft24_ams_slave14_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave14_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave14_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave14_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave14_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave14_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave14_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave14_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave14_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave14_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave14_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave14_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave13_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave13_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave13_status_unpack(
+ struct can1__main_ft24_ams_slave13_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave13_status_init(struct can1__main_ft24_ams_slave13_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave13_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave13_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave13_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave13_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave13_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave13_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave13_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave13_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave13_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave13_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave13_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave12_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave12_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave12_status_unpack(
+ struct can1__main_ft24_ams_slave12_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave12_status_init(struct can1__main_ft24_ams_slave12_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave12_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave12_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave12_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave12_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave12_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave12_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave12_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave12_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave12_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave12_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave12_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave11_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave11_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave11_status_unpack(
+ struct can1__main_ft24_ams_slave11_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave11_status_init(struct can1__main_ft24_ams_slave11_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave11_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave11_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave11_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave11_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave11_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave11_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave11_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave11_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave11_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave11_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave11_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave10_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave10_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave10_status_unpack(
+ struct can1__main_ft24_ams_slave10_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave10_status_init(struct can1__main_ft24_ams_slave10_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave10_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave10_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave10_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave10_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave10_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave10_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave10_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave10_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave10_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave10_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave10_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave9_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave9_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave9_status_unpack(
+ struct can1__main_ft24_ams_slave9_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave9_status_init(struct can1__main_ft24_ams_slave9_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave9_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave9_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave9_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave9_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave9_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave9_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave9_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave9_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave9_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave9_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave9_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave8_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave8_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave8_status_unpack(
+ struct can1__main_ft24_ams_slave8_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave8_status_init(struct can1__main_ft24_ams_slave8_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave8_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave8_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave8_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave8_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave8_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave8_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave8_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave8_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave8_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave8_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave8_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave7_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave7_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave7_status_unpack(
+ struct can1__main_ft24_ams_slave7_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave7_status_init(struct can1__main_ft24_ams_slave7_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave7_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave7_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave7_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave7_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave7_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave7_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave7_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave7_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave7_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave7_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave7_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave6_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave6_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave6_status_unpack(
+ struct can1__main_ft24_ams_slave6_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave6_status_init(struct can1__main_ft24_ams_slave6_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave6_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave6_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave6_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave6_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave6_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave6_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave6_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave6_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave6_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave6_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave6_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave5_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave5_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave5_status_unpack(
+ struct can1__main_ft24_ams_slave5_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave5_status_init(struct can1__main_ft24_ams_slave5_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave5_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave5_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave5_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave5_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave5_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave5_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave5_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave5_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave5_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave5_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave5_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave4_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave4_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave4_status_unpack(
+ struct can1__main_ft24_ams_slave4_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave4_status_init(struct can1__main_ft24_ams_slave4_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave4_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave4_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave4_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave4_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave4_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave4_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave4_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave4_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave4_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave4_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave4_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave3_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave3_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave3_status_unpack(
+ struct can1__main_ft24_ams_slave3_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave3_status_init(struct can1__main_ft24_ams_slave3_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave3_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave3_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave3_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave3_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave3_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave3_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave3_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave3_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave3_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave3_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave3_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave2_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave2_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave2_status_unpack(
+ struct can1__main_ft24_ams_slave2_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave2_status_init(struct can1__main_ft24_ams_slave2_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave2_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave2_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave2_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave2_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave2_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave2_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave2_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave2_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave2_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave2_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave2_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ams_slave1_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave1_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave1_status_unpack(
+ struct can1__main_ft24_ams_slave1_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave1_status_init(struct can1__main_ft24_ams_slave1_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave1_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave1_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave1_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave1_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave1_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave1_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave1_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave1_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave1_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave1_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave1_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_abx_misc_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_misc_t *src_p,
+ size_t size)
+{
+ if (size < 7u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 7);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->abx_driver_protocol, 0u, 0x07u);
+ dst_p[1] |= pack_left_shift_u16(src_p->abx_distance_session, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->abx_distance_session, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->abx_distance_total, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->abx_distance_total, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->abx_lv_so_c, 0u, 0xffu);
+ dst_p[6] |= pack_left_shift_u8(src_p->abx_lv_voltage, 0u, 0xffu);
+
+ return (7);
+}
+
+int can1__main_ft24_abx_misc_unpack(
+ struct can1__main_ft24_abx_misc_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 7u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_driver_protocol = unpack_right_shift_u8(src_p[0], 0u, 0x07u);
+ dst_p->abx_distance_session = unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->abx_distance_session |= unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->abx_distance_total = unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->abx_distance_total |= unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->abx_lv_so_c = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->abx_lv_voltage = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_misc_init(struct can1__main_ft24_abx_misc_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_misc_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_abx_misc_abx_driver_protocol_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_abx_misc_abx_driver_protocol_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_misc_abx_driver_protocol_is_in_range(uint8_t value)
+{
+ return (value <= 7u);
+}
+
+uint16_t can1__main_ft24_abx_misc_abx_distance_session_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_abx_misc_abx_distance_session_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_misc_abx_distance_session_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_misc_abx_distance_total_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_misc_abx_distance_total_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_misc_abx_distance_total_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_abx_misc_abx_lv_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_abx_misc_abx_lv_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_misc_abx_lv_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 100u);
+}
+
+uint8_t can1__main_ft24_abx_misc_abx_lv_voltage_encode(double value)
+{
+ return (uint8_t)(value / 0.0588235294117647);
+}
+
+double can1__main_ft24_abx_misc_abx_lv_voltage_decode(uint8_t value)
+{
+ return ((double)value * 0.0588235294117647);
+}
+
+bool can1__main_ft24_abx_misc_abx_lv_voltage_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_error_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_error_t *src_p,
+ size_t size)
+{
+ uint8_t ams_error_arg;
+ uint8_t ams_error_kind;
+
+ if (size < 2u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 2);
+
+ ams_error_kind = (uint8_t)src_p->ams_error_kind;
+ dst_p[0] |= pack_left_shift_u8(ams_error_kind, 0u, 0xffu);
+ ams_error_arg = (uint8_t)src_p->ams_error_arg;
+ dst_p[1] |= pack_left_shift_u8(ams_error_arg, 0u, 0xffu);
+
+ return (2);
+}
+
+int can1__main_ft24_ams_error_unpack(
+ struct can1__main_ft24_ams_error_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t ams_error_arg;
+ uint8_t ams_error_kind;
+
+ if (size < 2u) {
+ return (-EINVAL);
+ }
+
+ ams_error_kind = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_error_kind = (int8_t)ams_error_kind;
+ ams_error_arg = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_error_arg = (int8_t)ams_error_arg;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_error_init(struct can1__main_ft24_ams_error_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_error_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_ams_error_ams_error_kind_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_error_ams_error_kind_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_error_ams_error_kind_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int8_t can1__main_ft24_ams_error_ams_error_arg_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_ams_error_ams_error_arg_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_error_ams_error_arg_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_abx_cooling_sys_internal_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_cooling_sys_internal_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u16(src_p->abx_cs_t_inv_l, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(src_p->abx_cs_t_inv_l, 8u, 0xffu);
+ dst_p[2] |= pack_left_shift_u16(src_p->abx_cs_t_inv_r, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(src_p->abx_cs_t_inv_r, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u16(src_p->abx_cs_t_mot_l, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->abx_cs_t_mot_l, 8u, 0xffu);
+ dst_p[6] |= pack_left_shift_u16(src_p->abx_cs_t_mot_r, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(src_p->abx_cs_t_mot_r, 8u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_cooling_sys_internal_unpack(
+ struct can1__main_ft24_abx_cooling_sys_internal_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_cs_t_inv_l = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ dst_p->abx_cs_t_inv_l |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->abx_cs_t_inv_r = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ dst_p->abx_cs_t_inv_r |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->abx_cs_t_mot_l = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->abx_cs_t_mot_l |= unpack_left_shift_u16(src_p[5], 8u, 0xffu);
+ dst_p->abx_cs_t_mot_r = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ dst_p->abx_cs_t_mot_r |= unpack_left_shift_u16(src_p[7], 8u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_cooling_sys_internal_init(struct can1__main_ft24_abx_cooling_sys_internal_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_cooling_sys_internal_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_l_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_l_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_l_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_r_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_r_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_inv_r_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_l_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_l_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_l_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_r_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_r_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_cooling_sys_internal_abx_cs_t_mot_r_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_abx_cooling_sys_acc_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_cooling_sys_acc_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->abx_cs_p_acc_in, 0u, 0xffu);
+ dst_p[1] |= pack_left_shift_u8(src_p->abx_cs_p_acc_out, 0u, 0xffu);
+ dst_p[2] |= pack_left_shift_u16(src_p->abx_cs_t_acc_in, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(src_p->abx_cs_t_acc_in, 8u, 0x03u);
+ dst_p[4] |= pack_left_shift_u16(src_p->abx_cs_t_acc_out, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->abx_cs_t_acc_out, 8u, 0x03u);
+
+ return (6);
+}
+
+int can1__main_ft24_abx_cooling_sys_acc_unpack(
+ struct can1__main_ft24_abx_cooling_sys_acc_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_cs_p_acc_in = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->abx_cs_p_acc_out = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->abx_cs_t_acc_in = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ dst_p->abx_cs_t_acc_in |= unpack_left_shift_u16(src_p[3], 8u, 0x03u);
+ dst_p->abx_cs_t_acc_out = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->abx_cs_t_acc_out |= unpack_left_shift_u16(src_p[5], 8u, 0x03u);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_cooling_sys_acc_init(struct can1__main_ft24_abx_cooling_sys_acc_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_cooling_sys_acc_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_in_encode(double value)
+{
+ return (uint8_t)(value / 0.02);
+}
+
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_in_decode(uint8_t value)
+{
+ return ((double)value * 0.02);
+}
+
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_in_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+uint8_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_out_encode(double value)
+{
+ return (uint8_t)(value / 0.02);
+}
+
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_out_decode(uint8_t value)
+{
+ return ((double)value * 0.02);
+}
+
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_p_acc_out_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_in_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_in_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_in_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_out_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_out_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_cooling_sys_acc_abx_cs_t_acc_out_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+int can1__main_ft24_abx_cooling_sys_mot_inv_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_cooling_sys_mot_inv_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->abx_cs_p_inv_in, 0u, 0xffu);
+ dst_p[1] |= pack_left_shift_u8(src_p->abx_cs_p_mot_l_in, 0u, 0xffu);
+ dst_p[2] |= pack_left_shift_u8(src_p->abx_cs_p_rad_in, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->abx_cs_p_mot_r_in, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u16(src_p->abx_cs_t_inv_in, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->abx_cs_t_inv_in, 8u, 0x03u);
+ dst_p[5] |= pack_left_shift_u16(src_p->abx_cs_t_mot_in, 2u, 0xfcu);
+ dst_p[6] |= pack_right_shift_u16(src_p->abx_cs_t_mot_in, 6u, 0x0fu);
+ dst_p[6] |= pack_left_shift_u16(src_p->abx_cs_t_rad_in, 4u, 0xf0u);
+ dst_p[7] |= pack_right_shift_u16(src_p->abx_cs_t_rad_in, 4u, 0x3fu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_cooling_sys_mot_inv_unpack(
+ struct can1__main_ft24_abx_cooling_sys_mot_inv_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_cs_p_inv_in = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->abx_cs_p_mot_l_in = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->abx_cs_p_rad_in = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->abx_cs_p_mot_r_in = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->abx_cs_t_inv_in = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->abx_cs_t_inv_in |= unpack_left_shift_u16(src_p[5], 8u, 0x03u);
+ dst_p->abx_cs_t_mot_in = unpack_right_shift_u16(src_p[5], 2u, 0xfcu);
+ dst_p->abx_cs_t_mot_in |= unpack_left_shift_u16(src_p[6], 6u, 0x0fu);
+ dst_p->abx_cs_t_rad_in = unpack_right_shift_u16(src_p[6], 4u, 0xf0u);
+ dst_p->abx_cs_t_rad_in |= unpack_left_shift_u16(src_p[7], 4u, 0x3fu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_cooling_sys_mot_inv_init(struct can1__main_ft24_abx_cooling_sys_mot_inv_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_cooling_sys_mot_inv_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_inv_in_encode(double value)
+{
+ return (uint8_t)(value / 0.02);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_inv_in_decode(uint8_t value)
+{
+ return ((double)value * 0.02);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_inv_in_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_l_in_encode(double value)
+{
+ return (uint8_t)(value / 0.02);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_l_in_decode(uint8_t value)
+{
+ return ((double)value * 0.02);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_l_in_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_rad_in_encode(double value)
+{
+ return (uint8_t)(value / 0.02);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_rad_in_decode(uint8_t value)
+{
+ return ((double)value * 0.02);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_rad_in_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+uint8_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_r_in_encode(double value)
+{
+ return (uint8_t)(value / 0.02);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_r_in_decode(uint8_t value)
+{
+ return ((double)value * 0.02);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_p_mot_r_in_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_inv_in_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_inv_in_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_inv_in_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_mot_in_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_mot_in_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_mot_in_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+uint16_t can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_rad_in_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_rad_in_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_cooling_sys_mot_inv_abx_cs_t_rad_in_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+int can1__main_ft24_abx_brake_t_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_brake_t_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u16(src_p->abx_brake_t_fl, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(src_p->abx_brake_t_fl, 8u, 0xffu);
+ dst_p[2] |= pack_left_shift_u16(src_p->abx_brake_t_fr, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(src_p->abx_brake_t_fr, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u16(src_p->abx_brake_t_rl, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->abx_brake_t_rl, 8u, 0xffu);
+ dst_p[6] |= pack_left_shift_u16(src_p->abx_brake_t_rr, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(src_p->abx_brake_t_rr, 8u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_brake_t_unpack(
+ struct can1__main_ft24_abx_brake_t_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_brake_t_fl = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ dst_p->abx_brake_t_fl |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->abx_brake_t_fr = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ dst_p->abx_brake_t_fr |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->abx_brake_t_rl = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->abx_brake_t_rl |= unpack_left_shift_u16(src_p[5], 8u, 0xffu);
+ dst_p->abx_brake_t_rr = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ dst_p->abx_brake_t_rr |= unpack_left_shift_u16(src_p[7], 8u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_brake_t_init(struct can1__main_ft24_abx_brake_t_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_brake_t_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_fl_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_brake_t_abx_brake_t_fl_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_brake_t_abx_brake_t_fl_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_fr_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_brake_t_abx_brake_t_fr_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_brake_t_abx_brake_t_fr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_rl_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_brake_t_abx_brake_t_rl_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_brake_t_abx_brake_t_rl_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_brake_t_abx_brake_t_rr_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_brake_t_abx_brake_t_rr_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_brake_t_abx_brake_t_rr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_abx_wheelspeed_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_wheelspeed_t *src_p,
+ size_t size)
+{
+ uint16_t abx_wheelspeed_fl;
+ uint16_t abx_wheelspeed_fr;
+ uint16_t abx_wheelspeed_rl;
+ uint16_t abx_wheelspeed_rr;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ abx_wheelspeed_fl = (uint16_t)src_p->abx_wheelspeed_fl;
+ dst_p[0] |= pack_left_shift_u16(abx_wheelspeed_fl, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(abx_wheelspeed_fl, 8u, 0xffu);
+ abx_wheelspeed_fr = (uint16_t)src_p->abx_wheelspeed_fr;
+ dst_p[2] |= pack_left_shift_u16(abx_wheelspeed_fr, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(abx_wheelspeed_fr, 8u, 0xffu);
+ abx_wheelspeed_rl = (uint16_t)src_p->abx_wheelspeed_rl;
+ dst_p[4] |= pack_left_shift_u16(abx_wheelspeed_rl, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(abx_wheelspeed_rl, 8u, 0xffu);
+ abx_wheelspeed_rr = (uint16_t)src_p->abx_wheelspeed_rr;
+ dst_p[6] |= pack_left_shift_u16(abx_wheelspeed_rr, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(abx_wheelspeed_rr, 8u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_wheelspeed_unpack(
+ struct can1__main_ft24_abx_wheelspeed_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t abx_wheelspeed_fl;
+ uint16_t abx_wheelspeed_fr;
+ uint16_t abx_wheelspeed_rl;
+ uint16_t abx_wheelspeed_rr;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ abx_wheelspeed_fl = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ abx_wheelspeed_fl |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->abx_wheelspeed_fl = (int16_t)abx_wheelspeed_fl;
+ abx_wheelspeed_fr = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ abx_wheelspeed_fr |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->abx_wheelspeed_fr = (int16_t)abx_wheelspeed_fr;
+ abx_wheelspeed_rl = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ abx_wheelspeed_rl |= unpack_left_shift_u16(src_p[5], 8u, 0xffu);
+ dst_p->abx_wheelspeed_rl = (int16_t)abx_wheelspeed_rl;
+ abx_wheelspeed_rr = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ abx_wheelspeed_rr |= unpack_left_shift_u16(src_p[7], 8u, 0xffu);
+ dst_p->abx_wheelspeed_rr = (int16_t)abx_wheelspeed_rr;
+
+ return (0);
+}
+
+int can1__main_ft24_abx_wheelspeed_init(struct can1__main_ft24_abx_wheelspeed_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_wheelspeed_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fl_encode(double value)
+{
+ return (int16_t)(value / 0.001);
+}
+
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fl_decode(int16_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fl_is_in_range(int16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fr_encode(double value)
+{
+ return (int16_t)(value / 0.001);
+}
+
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fr_decode(int16_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_fr_is_in_range(int16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rl_encode(double value)
+{
+ return (int16_t)(value / 0.001);
+}
+
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rl_decode(int16_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rl_is_in_range(int16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int16_t can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rr_encode(double value)
+{
+ return (int16_t)(value / 0.001);
+}
+
+double can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rr_decode(int16_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_abx_wheelspeed_abx_wheelspeed_rr_is_in_range(int16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_abx_dampers_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_dampers_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u16(src_p->abx_damper_heave_f, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(src_p->abx_damper_heave_f, 8u, 0xffu);
+ dst_p[2] |= pack_left_shift_u16(src_p->abx_damper_roll_f, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(src_p->abx_damper_roll_f, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u16(src_p->abx_damper_heave_r, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->abx_damper_heave_r, 8u, 0xffu);
+ dst_p[6] |= pack_left_shift_u16(src_p->abx_damper_roll_r, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(src_p->abx_damper_roll_r, 8u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_dampers_unpack(
+ struct can1__main_ft24_abx_dampers_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_damper_heave_f = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ dst_p->abx_damper_heave_f |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->abx_damper_roll_f = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ dst_p->abx_damper_roll_f |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->abx_damper_heave_r = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->abx_damper_heave_r |= unpack_left_shift_u16(src_p[5], 8u, 0xffu);
+ dst_p->abx_damper_roll_r = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ dst_p->abx_damper_roll_r |= unpack_left_shift_u16(src_p[7], 8u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_dampers_init(struct can1__main_ft24_abx_dampers_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_dampers_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_abx_dampers_abx_damper_heave_f_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_dampers_abx_damper_heave_f_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_dampers_abx_damper_heave_f_is_in_range(uint16_t value)
+{
+ return (value <= 7500u);
+}
+
+uint16_t can1__main_ft24_abx_dampers_abx_damper_roll_f_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_dampers_abx_damper_roll_f_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_dampers_abx_damper_roll_f_is_in_range(uint16_t value)
+{
+ return (value <= 7500u);
+}
+
+uint16_t can1__main_ft24_abx_dampers_abx_damper_heave_r_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_dampers_abx_damper_heave_r_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_dampers_abx_damper_heave_r_is_in_range(uint16_t value)
+{
+ return (value <= 7500u);
+}
+
+uint16_t can1__main_ft24_abx_dampers_abx_damper_roll_r_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_dampers_abx_damper_roll_r_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_dampers_abx_damper_roll_r_is_in_range(uint16_t value)
+{
+ return (value <= 7500u);
+}
+
+int can1__main_ft24_abx_timings_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_timings_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u16(src_p->abx_laptime_best, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(src_p->abx_laptime_best, 8u, 0xffu);
+ dst_p[2] |= pack_left_shift_u16(src_p->abx_laptime_last, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(src_p->abx_laptime_last, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u16(src_p->abx_sectortime_best, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->abx_sectortime_best, 8u, 0xffu);
+ dst_p[6] |= pack_left_shift_u16(src_p->abx_sectortime_last, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(src_p->abx_sectortime_last, 8u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_timings_unpack(
+ struct can1__main_ft24_abx_timings_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_laptime_best = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ dst_p->abx_laptime_best |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->abx_laptime_last = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ dst_p->abx_laptime_last |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->abx_sectortime_best = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->abx_sectortime_best |= unpack_left_shift_u16(src_p[5], 8u, 0xffu);
+ dst_p->abx_sectortime_last = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ dst_p->abx_sectortime_last |= unpack_left_shift_u16(src_p[7], 8u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_timings_init(struct can1__main_ft24_abx_timings_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_timings_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_abx_timings_abx_laptime_best_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_timings_abx_laptime_best_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_timings_abx_laptime_best_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_timings_abx_laptime_last_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_timings_abx_laptime_last_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_timings_abx_laptime_last_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_timings_abx_sectortime_best_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_timings_abx_sectortime_best_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_timings_abx_sectortime_best_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_abx_timings_abx_sectortime_last_encode(double value)
+{
+ return (uint16_t)(value / 0.01);
+}
+
+double can1__main_ft24_abx_timings_abx_sectortime_last_decode(uint16_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_abx_timings_abx_sectortime_last_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_abx_driver_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_abx_driver_t *src_p,
+ size_t size)
+{
+ uint8_t abx_steering_angle;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->abx_apps_percent, 0u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->abx_brake_p_f, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->abx_brake_p_f, 8u, 0x0fu);
+ dst_p[2] |= pack_left_shift_u16(src_p->abx_brake_p_r, 4u, 0xf0u);
+ dst_p[3] |= pack_right_shift_u16(src_p->abx_brake_p_r, 4u, 0xffu);
+ abx_steering_angle = (uint8_t)src_p->abx_steering_angle;
+ dst_p[4] |= pack_left_shift_u8(abx_steering_angle, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->abx_speed, 0u, 0xffu);
+ dst_p[6] |= pack_left_shift_u8(src_p->abx_lapcounter, 0u, 0xffu);
+ dst_p[7] |= pack_left_shift_u8(src_p->abx_sectorcounter, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_abx_driver_unpack(
+ struct can1__main_ft24_abx_driver_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t abx_steering_angle;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->abx_apps_percent = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->abx_brake_p_f = unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->abx_brake_p_f |= unpack_left_shift_u16(src_p[2], 8u, 0x0fu);
+ dst_p->abx_brake_p_r = unpack_right_shift_u16(src_p[2], 4u, 0xf0u);
+ dst_p->abx_brake_p_r |= unpack_left_shift_u16(src_p[3], 4u, 0xffu);
+ abx_steering_angle = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->abx_steering_angle = (int8_t)abx_steering_angle;
+ dst_p->abx_speed = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->abx_lapcounter = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ dst_p->abx_sectorcounter = unpack_right_shift_u8(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_abx_driver_init(struct can1__main_ft24_abx_driver_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_abx_driver_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_abx_driver_abx_apps_percent_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_abx_driver_abx_apps_percent_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_driver_abx_apps_percent_is_in_range(uint8_t value)
+{
+ return (value <= 100u);
+}
+
+uint16_t can1__main_ft24_abx_driver_abx_brake_p_f_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_driver_abx_brake_p_f_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_driver_abx_brake_p_f_is_in_range(uint16_t value)
+{
+ return (value <= 1600u);
+}
+
+uint16_t can1__main_ft24_abx_driver_abx_brake_p_r_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_abx_driver_abx_brake_p_r_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_abx_driver_abx_brake_p_r_is_in_range(uint16_t value)
+{
+ return (value <= 1600u);
+}
+
+int8_t can1__main_ft24_abx_driver_abx_steering_angle_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_abx_driver_abx_steering_angle_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_driver_abx_steering_angle_is_in_range(int8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_abx_driver_abx_speed_encode(double value)
+{
+ return (uint8_t)(value / 0.2);
+}
+
+double can1__main_ft24_abx_driver_abx_speed_decode(uint8_t value)
+{
+ return ((double)value * 0.2);
+}
+
+bool can1__main_ft24_abx_driver_abx_speed_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_abx_driver_abx_lapcounter_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_abx_driver_abx_lapcounter_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_driver_abx_lapcounter_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_abx_driver_abx_sectorcounter_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_abx_driver_abx_sectorcounter_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_abx_driver_abx_sectorcounter_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_tts_config_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_config_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->tts_new_id, 0u, 0x03u);
+
+ return (1);
+}
+
+int can1__main_ft24_tts_config_unpack(
+ struct can1__main_ft24_tts_config_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->tts_new_id = unpack_right_shift_u8(src_p[0], 0u, 0x03u);
+
+ return (0);
+}
+
+int can1__main_ft24_tts_config_init(struct can1__main_ft24_tts_config_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_tts_config_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_tts_config_tts_new_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tts_config_tts_new_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tts_config_tts_new_id_is_in_range(uint8_t value)
+{
+ return (value <= 3u);
+}
+
+int can1__main_ft24_tts_rr_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_rr_t *src_p,
+ size_t size)
+{
+ uint16_t tts_rr_center;
+ uint16_t tts_rr_center_in;
+ uint16_t tts_rr_center_out;
+ uint16_t tts_rr_inner;
+ uint16_t tts_rr_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ tts_rr_inner = (uint16_t)src_p->tts_rr_inner;
+ dst_p[0] |= pack_left_shift_u16(tts_rr_inner, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(tts_rr_inner, 8u, 0x0fu);
+ tts_rr_center_in = (uint16_t)src_p->tts_rr_center_in;
+ dst_p[1] |= pack_left_shift_u16(tts_rr_center_in, 4u, 0xf0u);
+ dst_p[2] |= pack_right_shift_u16(tts_rr_center_in, 4u, 0xffu);
+ tts_rr_center = (uint16_t)src_p->tts_rr_center;
+ dst_p[3] |= pack_left_shift_u16(tts_rr_center, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(tts_rr_center, 8u, 0x0fu);
+ tts_rr_center_out = (uint16_t)src_p->tts_rr_center_out;
+ dst_p[4] |= pack_left_shift_u16(tts_rr_center_out, 4u, 0xf0u);
+ dst_p[5] |= pack_right_shift_u16(tts_rr_center_out, 4u, 0xffu);
+ tts_rr_outer = (uint16_t)src_p->tts_rr_outer;
+ dst_p[6] |= pack_left_shift_u16(tts_rr_outer, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(tts_rr_outer, 8u, 0x0fu);
+
+ return (8);
+}
+
+int can1__main_ft24_tts_rr_unpack(
+ struct can1__main_ft24_tts_rr_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t tts_rr_center;
+ uint16_t tts_rr_center_in;
+ uint16_t tts_rr_center_out;
+ uint16_t tts_rr_inner;
+ uint16_t tts_rr_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ tts_rr_inner = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ tts_rr_inner |= unpack_left_shift_u16(src_p[1], 8u, 0x0fu);
+
+ if ((tts_rr_inner & (1u << 11)) != 0u) {
+ tts_rr_inner |= 0xf000u;
+ }
+
+ dst_p->tts_rr_inner = (int16_t)tts_rr_inner;
+ tts_rr_center_in = unpack_right_shift_u16(src_p[1], 4u, 0xf0u);
+ tts_rr_center_in |= unpack_left_shift_u16(src_p[2], 4u, 0xffu);
+
+ if ((tts_rr_center_in & (1u << 11)) != 0u) {
+ tts_rr_center_in |= 0xf000u;
+ }
+
+ dst_p->tts_rr_center_in = (int16_t)tts_rr_center_in;
+ tts_rr_center = unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ tts_rr_center |= unpack_left_shift_u16(src_p[4], 8u, 0x0fu);
+
+ if ((tts_rr_center & (1u << 11)) != 0u) {
+ tts_rr_center |= 0xf000u;
+ }
+
+ dst_p->tts_rr_center = (int16_t)tts_rr_center;
+ tts_rr_center_out = unpack_right_shift_u16(src_p[4], 4u, 0xf0u);
+ tts_rr_center_out |= unpack_left_shift_u16(src_p[5], 4u, 0xffu);
+
+ if ((tts_rr_center_out & (1u << 11)) != 0u) {
+ tts_rr_center_out |= 0xf000u;
+ }
+
+ dst_p->tts_rr_center_out = (int16_t)tts_rr_center_out;
+ tts_rr_outer = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ tts_rr_outer |= unpack_left_shift_u16(src_p[7], 8u, 0x0fu);
+
+ if ((tts_rr_outer & (1u << 11)) != 0u) {
+ tts_rr_outer |= 0xf000u;
+ }
+
+ dst_p->tts_rr_outer = (int16_t)tts_rr_outer;
+
+ return (0);
+}
+
+int can1__main_ft24_tts_rr_init(struct can1__main_ft24_tts_rr_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_tts_rr_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_tts_rr_tts_rr_inner_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rr_tts_rr_inner_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rr_tts_rr_inner_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rr_tts_rr_center_in_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rr_tts_rr_center_in_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rr_tts_rr_center_in_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rr_tts_rr_center_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rr_tts_rr_center_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rr_tts_rr_center_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rr_tts_rr_center_out_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rr_tts_rr_center_out_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rr_tts_rr_center_out_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rr_tts_rr_outer_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rr_tts_rr_outer_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rr_tts_rr_outer_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int can1__main_ft24_tts_rl_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_rl_t *src_p,
+ size_t size)
+{
+ uint16_t tts_rl_center;
+ uint16_t tts_rl_center_in;
+ uint16_t tts_rl_center_out;
+ uint16_t tts_rl_inner;
+ uint16_t tts_rl_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ tts_rl_outer = (uint16_t)src_p->tts_rl_outer;
+ dst_p[0] |= pack_left_shift_u16(tts_rl_outer, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(tts_rl_outer, 8u, 0x0fu);
+ tts_rl_center_out = (uint16_t)src_p->tts_rl_center_out;
+ dst_p[1] |= pack_left_shift_u16(tts_rl_center_out, 4u, 0xf0u);
+ dst_p[2] |= pack_right_shift_u16(tts_rl_center_out, 4u, 0xffu);
+ tts_rl_center = (uint16_t)src_p->tts_rl_center;
+ dst_p[3] |= pack_left_shift_u16(tts_rl_center, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(tts_rl_center, 8u, 0x0fu);
+ tts_rl_center_in = (uint16_t)src_p->tts_rl_center_in;
+ dst_p[4] |= pack_left_shift_u16(tts_rl_center_in, 4u, 0xf0u);
+ dst_p[5] |= pack_right_shift_u16(tts_rl_center_in, 4u, 0xffu);
+ tts_rl_inner = (uint16_t)src_p->tts_rl_inner;
+ dst_p[6] |= pack_left_shift_u16(tts_rl_inner, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(tts_rl_inner, 8u, 0x0fu);
+
+ return (8);
+}
+
+int can1__main_ft24_tts_rl_unpack(
+ struct can1__main_ft24_tts_rl_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t tts_rl_center;
+ uint16_t tts_rl_center_in;
+ uint16_t tts_rl_center_out;
+ uint16_t tts_rl_inner;
+ uint16_t tts_rl_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ tts_rl_outer = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ tts_rl_outer |= unpack_left_shift_u16(src_p[1], 8u, 0x0fu);
+
+ if ((tts_rl_outer & (1u << 11)) != 0u) {
+ tts_rl_outer |= 0xf000u;
+ }
+
+ dst_p->tts_rl_outer = (int16_t)tts_rl_outer;
+ tts_rl_center_out = unpack_right_shift_u16(src_p[1], 4u, 0xf0u);
+ tts_rl_center_out |= unpack_left_shift_u16(src_p[2], 4u, 0xffu);
+
+ if ((tts_rl_center_out & (1u << 11)) != 0u) {
+ tts_rl_center_out |= 0xf000u;
+ }
+
+ dst_p->tts_rl_center_out = (int16_t)tts_rl_center_out;
+ tts_rl_center = unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ tts_rl_center |= unpack_left_shift_u16(src_p[4], 8u, 0x0fu);
+
+ if ((tts_rl_center & (1u << 11)) != 0u) {
+ tts_rl_center |= 0xf000u;
+ }
+
+ dst_p->tts_rl_center = (int16_t)tts_rl_center;
+ tts_rl_center_in = unpack_right_shift_u16(src_p[4], 4u, 0xf0u);
+ tts_rl_center_in |= unpack_left_shift_u16(src_p[5], 4u, 0xffu);
+
+ if ((tts_rl_center_in & (1u << 11)) != 0u) {
+ tts_rl_center_in |= 0xf000u;
+ }
+
+ dst_p->tts_rl_center_in = (int16_t)tts_rl_center_in;
+ tts_rl_inner = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ tts_rl_inner |= unpack_left_shift_u16(src_p[7], 8u, 0x0fu);
+
+ if ((tts_rl_inner & (1u << 11)) != 0u) {
+ tts_rl_inner |= 0xf000u;
+ }
+
+ dst_p->tts_rl_inner = (int16_t)tts_rl_inner;
+
+ return (0);
+}
+
+int can1__main_ft24_tts_rl_init(struct can1__main_ft24_tts_rl_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_tts_rl_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_tts_rl_tts_rl_outer_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rl_tts_rl_outer_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rl_tts_rl_outer_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rl_tts_rl_center_out_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rl_tts_rl_center_out_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rl_tts_rl_center_out_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rl_tts_rl_center_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rl_tts_rl_center_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rl_tts_rl_center_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rl_tts_rl_center_in_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rl_tts_rl_center_in_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rl_tts_rl_center_in_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_rl_tts_rl_inner_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_rl_tts_rl_inner_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_rl_tts_rl_inner_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int can1__main_ft24_tts_fr_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_fr_t *src_p,
+ size_t size)
+{
+ uint16_t tts_fr_center;
+ uint16_t tts_fr_center_in;
+ uint16_t tts_fr_center_out;
+ uint16_t tts_fr_inner;
+ uint16_t tts_fr_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ tts_fr_inner = (uint16_t)src_p->tts_fr_inner;
+ dst_p[0] |= pack_left_shift_u16(tts_fr_inner, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(tts_fr_inner, 8u, 0x0fu);
+ tts_fr_center_in = (uint16_t)src_p->tts_fr_center_in;
+ dst_p[1] |= pack_left_shift_u16(tts_fr_center_in, 4u, 0xf0u);
+ dst_p[2] |= pack_right_shift_u16(tts_fr_center_in, 4u, 0xffu);
+ tts_fr_center = (uint16_t)src_p->tts_fr_center;
+ dst_p[3] |= pack_left_shift_u16(tts_fr_center, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(tts_fr_center, 8u, 0x0fu);
+ tts_fr_center_out = (uint16_t)src_p->tts_fr_center_out;
+ dst_p[4] |= pack_left_shift_u16(tts_fr_center_out, 4u, 0xf0u);
+ dst_p[5] |= pack_right_shift_u16(tts_fr_center_out, 4u, 0xffu);
+ tts_fr_outer = (uint16_t)src_p->tts_fr_outer;
+ dst_p[6] |= pack_left_shift_u16(tts_fr_outer, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(tts_fr_outer, 8u, 0x0fu);
+
+ return (8);
+}
+
+int can1__main_ft24_tts_fr_unpack(
+ struct can1__main_ft24_tts_fr_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t tts_fr_center;
+ uint16_t tts_fr_center_in;
+ uint16_t tts_fr_center_out;
+ uint16_t tts_fr_inner;
+ uint16_t tts_fr_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ tts_fr_inner = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ tts_fr_inner |= unpack_left_shift_u16(src_p[1], 8u, 0x0fu);
+
+ if ((tts_fr_inner & (1u << 11)) != 0u) {
+ tts_fr_inner |= 0xf000u;
+ }
+
+ dst_p->tts_fr_inner = (int16_t)tts_fr_inner;
+ tts_fr_center_in = unpack_right_shift_u16(src_p[1], 4u, 0xf0u);
+ tts_fr_center_in |= unpack_left_shift_u16(src_p[2], 4u, 0xffu);
+
+ if ((tts_fr_center_in & (1u << 11)) != 0u) {
+ tts_fr_center_in |= 0xf000u;
+ }
+
+ dst_p->tts_fr_center_in = (int16_t)tts_fr_center_in;
+ tts_fr_center = unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ tts_fr_center |= unpack_left_shift_u16(src_p[4], 8u, 0x0fu);
+
+ if ((tts_fr_center & (1u << 11)) != 0u) {
+ tts_fr_center |= 0xf000u;
+ }
+
+ dst_p->tts_fr_center = (int16_t)tts_fr_center;
+ tts_fr_center_out = unpack_right_shift_u16(src_p[4], 4u, 0xf0u);
+ tts_fr_center_out |= unpack_left_shift_u16(src_p[5], 4u, 0xffu);
+
+ if ((tts_fr_center_out & (1u << 11)) != 0u) {
+ tts_fr_center_out |= 0xf000u;
+ }
+
+ dst_p->tts_fr_center_out = (int16_t)tts_fr_center_out;
+ tts_fr_outer = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ tts_fr_outer |= unpack_left_shift_u16(src_p[7], 8u, 0x0fu);
+
+ if ((tts_fr_outer & (1u << 11)) != 0u) {
+ tts_fr_outer |= 0xf000u;
+ }
+
+ dst_p->tts_fr_outer = (int16_t)tts_fr_outer;
+
+ return (0);
+}
+
+int can1__main_ft24_tts_fr_init(struct can1__main_ft24_tts_fr_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_tts_fr_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_tts_fr_tts_fr_inner_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fr_tts_fr_inner_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fr_tts_fr_inner_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fr_tts_fr_center_in_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fr_tts_fr_center_in_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fr_tts_fr_center_in_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fr_tts_fr_center_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fr_tts_fr_center_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fr_tts_fr_center_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fr_tts_fr_center_out_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fr_tts_fr_center_out_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fr_tts_fr_center_out_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fr_tts_fr_outer_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fr_tts_fr_outer_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fr_tts_fr_outer_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int can1__main_ft24_tts_fl_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tts_fl_t *src_p,
+ size_t size)
+{
+ uint16_t tts_fl_center;
+ uint16_t tts_fl_center_in;
+ uint16_t tts_fl_center_out;
+ uint16_t tts_fl_inner;
+ uint16_t tts_fl_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ tts_fl_outer = (uint16_t)src_p->tts_fl_outer;
+ dst_p[0] |= pack_left_shift_u16(tts_fl_outer, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(tts_fl_outer, 8u, 0x0fu);
+ tts_fl_center_out = (uint16_t)src_p->tts_fl_center_out;
+ dst_p[1] |= pack_left_shift_u16(tts_fl_center_out, 4u, 0xf0u);
+ dst_p[2] |= pack_right_shift_u16(tts_fl_center_out, 4u, 0xffu);
+ tts_fl_center = (uint16_t)src_p->tts_fl_center;
+ dst_p[3] |= pack_left_shift_u16(tts_fl_center, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(tts_fl_center, 8u, 0x0fu);
+ tts_fl_center_in = (uint16_t)src_p->tts_fl_center_in;
+ dst_p[4] |= pack_left_shift_u16(tts_fl_center_in, 4u, 0xf0u);
+ dst_p[5] |= pack_right_shift_u16(tts_fl_center_in, 4u, 0xffu);
+ tts_fl_inner = (uint16_t)src_p->tts_fl_inner;
+ dst_p[6] |= pack_left_shift_u16(tts_fl_inner, 0u, 0xffu);
+ dst_p[7] |= pack_right_shift_u16(tts_fl_inner, 8u, 0x0fu);
+
+ return (8);
+}
+
+int can1__main_ft24_tts_fl_unpack(
+ struct can1__main_ft24_tts_fl_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t tts_fl_center;
+ uint16_t tts_fl_center_in;
+ uint16_t tts_fl_center_out;
+ uint16_t tts_fl_inner;
+ uint16_t tts_fl_outer;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ tts_fl_outer = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ tts_fl_outer |= unpack_left_shift_u16(src_p[1], 8u, 0x0fu);
+
+ if ((tts_fl_outer & (1u << 11)) != 0u) {
+ tts_fl_outer |= 0xf000u;
+ }
+
+ dst_p->tts_fl_outer = (int16_t)tts_fl_outer;
+ tts_fl_center_out = unpack_right_shift_u16(src_p[1], 4u, 0xf0u);
+ tts_fl_center_out |= unpack_left_shift_u16(src_p[2], 4u, 0xffu);
+
+ if ((tts_fl_center_out & (1u << 11)) != 0u) {
+ tts_fl_center_out |= 0xf000u;
+ }
+
+ dst_p->tts_fl_center_out = (int16_t)tts_fl_center_out;
+ tts_fl_center = unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ tts_fl_center |= unpack_left_shift_u16(src_p[4], 8u, 0x0fu);
+
+ if ((tts_fl_center & (1u << 11)) != 0u) {
+ tts_fl_center |= 0xf000u;
+ }
+
+ dst_p->tts_fl_center = (int16_t)tts_fl_center;
+ tts_fl_center_in = unpack_right_shift_u16(src_p[4], 4u, 0xf0u);
+ tts_fl_center_in |= unpack_left_shift_u16(src_p[5], 4u, 0xffu);
+
+ if ((tts_fl_center_in & (1u << 11)) != 0u) {
+ tts_fl_center_in |= 0xf000u;
+ }
+
+ dst_p->tts_fl_center_in = (int16_t)tts_fl_center_in;
+ tts_fl_inner = unpack_right_shift_u16(src_p[6], 0u, 0xffu);
+ tts_fl_inner |= unpack_left_shift_u16(src_p[7], 8u, 0x0fu);
+
+ if ((tts_fl_inner & (1u << 11)) != 0u) {
+ tts_fl_inner |= 0xf000u;
+ }
+
+ dst_p->tts_fl_inner = (int16_t)tts_fl_inner;
+
+ return (0);
+}
+
+int can1__main_ft24_tts_fl_init(struct can1__main_ft24_tts_fl_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_tts_fl_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_tts_fl_tts_fl_outer_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fl_tts_fl_outer_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fl_tts_fl_outer_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fl_tts_fl_center_out_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fl_tts_fl_center_out_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fl_tts_fl_center_out_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fl_tts_fl_center_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fl_tts_fl_center_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fl_tts_fl_center_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fl_tts_fl_center_in_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fl_tts_fl_center_in_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fl_tts_fl_center_in_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int16_t can1__main_ft24_tts_fl_tts_fl_inner_encode(double value)
+{
+ return (int16_t)((value - 150.0) / 0.1);
+}
+
+double can1__main_ft24_tts_fl_tts_fl_inner_decode(int16_t value)
+{
+ return (((double)value * 0.1) + 150.0);
+}
+
+bool can1__main_ft24_tts_fl_tts_fl_inner_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+int can1__main_ft24_stw_param_set_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_param_set_t *src_p,
+ size_t size)
+{
+ if (size < 5u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 5);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->stw_param_type, 0u, 0xffu);
+
+ switch (src_p->stw_param_type) {
+
+ case 0:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_b_bal, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_b_bal, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_b_bal, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_b_bal, 0u, 0xffu);
+ break;
+
+ case 1:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_slipref, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_slipref, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_slipref, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_slipref, 0u, 0xffu);
+ break;
+
+ case 2:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_mumax, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_mumax, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_mumax, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_mumax, 0u, 0xffu);
+ break;
+
+ case 3:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_asrp, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_asrp, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_asrp, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_asrp, 0u, 0xffu);
+ break;
+
+ case 4:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_asron, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_asron, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_asron, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_asron, 0u, 0xffu);
+ break;
+
+ case 5:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_asri, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_asri, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_asri, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_asri, 0u, 0xffu);
+ break;
+
+ case 6:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_endu_power_limit, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_endu_power_limit, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_endu_power_limit, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_endu_power_limit, 0u, 0xffu);
+ break;
+
+ case 7:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_test3, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_test3, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_test3, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_test3, 0u, 0xffu);
+ break;
+
+ case 8:
+ dst_p[1] |= pack_right_shift_u32(src_p->stw_param_test4, 24u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->stw_param_test4, 16u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->stw_param_test4, 8u, 0xffu);
+ dst_p[4] |= pack_left_shift_u32(src_p->stw_param_test4, 0u, 0xffu);
+ break;
+
+ default:
+ break;
+ }
+
+ return (5);
+}
+
+int can1__main_ft24_stw_param_set_unpack(
+ struct can1__main_ft24_stw_param_set_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 5u) {
+ return (-EINVAL);
+ }
+
+ dst_p->stw_param_type = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+
+ switch (dst_p->stw_param_type) {
+
+ case 0:
+ dst_p->stw_param_b_bal = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_b_bal |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_b_bal |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_b_bal |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 1:
+ dst_p->stw_param_slipref = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_slipref |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_slipref |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_slipref |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 2:
+ dst_p->stw_param_mumax = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_mumax |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_mumax |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_mumax |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 3:
+ dst_p->stw_param_asrp = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_asrp |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_asrp |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_asrp |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 4:
+ dst_p->stw_param_asron = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_asron |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_asron |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_asron |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 5:
+ dst_p->stw_param_asri = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_asri |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_asri |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_asri |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 6:
+ dst_p->stw_param_endu_power_limit = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_endu_power_limit |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_endu_power_limit |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_endu_power_limit |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 7:
+ dst_p->stw_param_test3 = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_test3 |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_test3 |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_test3 |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ case 8:
+ dst_p->stw_param_test4 = unpack_left_shift_u32(src_p[1], 24u, 0xffu);
+ dst_p->stw_param_test4 |= unpack_left_shift_u32(src_p[2], 16u, 0xffu);
+ dst_p->stw_param_test4 |= unpack_left_shift_u32(src_p[3], 8u, 0xffu);
+ dst_p->stw_param_test4 |= unpack_right_shift_u32(src_p[4], 0u, 0xffu);
+ break;
+
+ default:
+ break;
+ }
+
+ return (0);
+}
+
+int can1__main_ft24_stw_param_set_init(struct can1__main_ft24_stw_param_set_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_stw_param_set_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_stw_param_set_stw_param_type_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_type_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_type_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_b_bal_encode(double value)
+{
+ return (uint32_t)(value / 0.1);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_b_bal_decode(uint32_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_b_bal_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_slipref_encode(double value)
+{
+ return (uint32_t)(value / 0.01);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_slipref_decode(uint32_t value)
+{
+ return ((double)value * 0.01);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_slipref_is_in_range(uint32_t value)
+{
+ return (value <= 100u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_asrp_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_asrp_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_asrp_is_in_range(uint32_t value)
+{
+ return (value <= 1u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_asron_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_asron_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_asron_is_in_range(uint32_t value)
+{
+ return (value <= 1u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_asri_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_asri_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_asri_is_in_range(uint32_t value)
+{
+ return (value <= 1u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_endu_power_limit_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_endu_power_limit_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_endu_power_limit_is_in_range(uint32_t value)
+{
+ return (value <= 1u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_test3_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_test3_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_test3_is_in_range(uint32_t value)
+{
+ return (value <= 1u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_test4_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_test4_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_test4_is_in_range(uint32_t value)
+{
+ return (value <= 1u);
+}
+
+uint32_t can1__main_ft24_stw_param_set_stw_param_mumax_encode(double value)
+{
+ return (uint32_t)(value / 0.1);
+}
+
+double can1__main_ft24_stw_param_set_stw_param_mumax_decode(uint32_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_stw_param_set_stw_param_mumax_is_in_range(uint32_t value)
+{
+ return (value <= 10u);
+}
+
+int can1__main_ft24_ams_slave0_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave0_status_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_error, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_status_id, 0u, 0x7fu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_status_so_c, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->ams_slave_status_min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->ams_slave_status_min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->ams_slave_status_max_cell_volt, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->ams_slave_status_max_cell_volt, 0u, 0xffu);
+ ams_slave_status_max_temp = (uint16_t)src_p->ams_slave_status_max_temp;
+ dst_p[6] |= pack_right_shift_u16(ams_slave_status_max_temp, 8u, 0x0fu);
+ dst_p[7] |= pack_left_shift_u16(ams_slave_status_max_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave0_status_unpack(
+ struct can1__main_ft24_ams_slave0_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ams_slave_status_max_temp;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_status_error = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->ams_slave_status_id = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->ams_slave_status_so_c = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->ams_slave_status_min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_status_max_cell_volt |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ ams_slave_status_max_temp = unpack_left_shift_u16(src_p[6], 8u, 0x0fu);
+ ams_slave_status_max_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ if ((ams_slave_status_max_temp & (1u << 11)) != 0u) {
+ ams_slave_status_max_temp |= 0xf000u;
+ }
+
+ dst_p->ams_slave_status_max_temp = (int16_t)ams_slave_status_max_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave0_status_init(struct can1__main_ft24_ams_slave0_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave0_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave0_status_ams_slave_status_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_status_ams_slave_status_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_slave0_status_ams_slave_status_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_status_ams_slave_status_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_id_is_in_range(uint8_t value)
+{
+ return (value <= 127u);
+}
+
+uint8_t can1__main_ft24_ams_slave0_status_ams_slave_status_so_c_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave0_status_ams_slave_status_so_c_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_so_c_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_ams_slave0_status_ams_slave_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_status_ams_slave_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+uint16_t can1__main_ft24_ams_slave0_status_ams_slave_status_max_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_slave0_status_ams_slave_status_max_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_max_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 10000u);
+}
+
+int16_t can1__main_ft24_ams_slave0_status_ams_slave_status_max_temp_encode(double value)
+{
+ return (int16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_slave0_status_ams_slave_status_max_temp_decode(int16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_slave0_status_ams_slave_status_max_temp_is_in_range(int16_t value)
+{
+ return ((value >= 0) && (value <= 16));
+}
+
+int can1__main_ft24_ssu_message_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ssu_message_t *src_p,
+ size_t size)
+{
+ uint16_t ssu_air_pressure;
+ uint16_t ssu_air_temp;
+
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 4);
+
+ ssu_air_pressure = (uint16_t)src_p->ssu_air_pressure;
+ dst_p[0] |= pack_left_shift_u16(ssu_air_pressure, 0u, 0xffu);
+ dst_p[1] |= pack_right_shift_u16(ssu_air_pressure, 8u, 0xffu);
+ ssu_air_temp = (uint16_t)src_p->ssu_air_temp;
+ dst_p[2] |= pack_left_shift_u16(ssu_air_temp, 0u, 0xffu);
+ dst_p[3] |= pack_right_shift_u16(ssu_air_temp, 8u, 0xffu);
+
+ return (4);
+}
+
+int can1__main_ft24_ssu_message_unpack(
+ struct can1__main_ft24_ssu_message_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t ssu_air_pressure;
+ uint16_t ssu_air_temp;
+
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ ssu_air_pressure = unpack_right_shift_u16(src_p[0], 0u, 0xffu);
+ ssu_air_pressure |= unpack_left_shift_u16(src_p[1], 8u, 0xffu);
+ dst_p->ssu_air_pressure = (int16_t)ssu_air_pressure;
+ ssu_air_temp = unpack_right_shift_u16(src_p[2], 0u, 0xffu);
+ ssu_air_temp |= unpack_left_shift_u16(src_p[3], 8u, 0xffu);
+ dst_p->ssu_air_temp = (int16_t)ssu_air_temp;
+
+ return (0);
+}
+
+int can1__main_ft24_ssu_message_init(struct can1__main_ft24_ssu_message_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ssu_message_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_ssu_message_ssu_air_pressure_encode(double value)
+{
+ return (int16_t)(value);
+}
+
+double can1__main_ft24_ssu_message_ssu_air_pressure_decode(int16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ssu_message_ssu_air_pressure_is_in_range(int16_t value)
+{
+ return ((value >= -1000) && (value <= 1000));
+}
+
+int16_t can1__main_ft24_ssu_message_ssu_air_temp_encode(double value)
+{
+ return (int16_t)(value / 0.1);
+}
+
+double can1__main_ft24_ssu_message_ssu_air_temp_decode(int16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_ssu_message_ssu_air_temp_is_in_range(int16_t value)
+{
+ return ((value >= -200) && (value <= 800));
+}
+
+int can1__main_ft24_ams_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_status_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_state, 0u, 0x7fu);
+ dst_p[0] |= pack_left_shift_u8(src_p->sdc_closed, 7u, 0x80u);
+ dst_p[1] |= pack_left_shift_u8(src_p->soc, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->min_cell_volt, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->min_cell_volt, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->max_cell_temp, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->max_cell_temp, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_ams_status_unpack(
+ struct can1__main_ft24_ams_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_state = unpack_right_shift_u8(src_p[0], 0u, 0x7fu);
+ dst_p->sdc_closed = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->soc = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->min_cell_volt = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->min_cell_volt |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->max_cell_temp = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->max_cell_temp |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_status_init(struct can1__main_ft24_ams_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_status_ams_state_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_status_ams_state_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_status_ams_state_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_status_sdc_closed_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_status_sdc_closed_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_status_sdc_closed_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_status_soc_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_status_soc_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_status_soc_is_in_range(uint8_t value)
+{
+ return (value <= 100u);
+}
+
+uint16_t can1__main_ft24_ams_status_min_cell_volt_encode(double value)
+{
+ return (uint16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_ams_status_min_cell_volt_decode(uint16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_ams_status_min_cell_volt_is_in_range(uint16_t value)
+{
+ return (value <= 50000u);
+}
+
+uint16_t can1__main_ft24_ams_status_max_cell_temp_encode(double value)
+{
+ return (uint16_t)(value / 0.0625);
+}
+
+double can1__main_ft24_ams_status_max_cell_temp_decode(uint16_t value)
+{
+ return ((double)value * 0.0625);
+}
+
+bool can1__main_ft24_ams_status_max_cell_temp_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_slave_panic_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_slave_panic_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ams_slave_panic_slave_id, 0u, 0xffu);
+ dst_p[1] |= pack_left_shift_u8(src_p->ams_slave_panic_kind, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->ams_slave_panic_arg, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->ams_slave_panic_arg, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->ams_slave_panic_arg, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->ams_slave_panic_arg, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_ams_slave_panic_unpack(
+ struct can1__main_ft24_ams_slave_panic_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ams_slave_panic_slave_id = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+ dst_p->ams_slave_panic_kind = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->ams_slave_panic_arg = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->ams_slave_panic_arg |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->ams_slave_panic_arg |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->ams_slave_panic_arg |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_slave_panic_init(struct can1__main_ft24_ams_slave_panic_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_slave_panic_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_slave_panic_ams_slave_panic_slave_id_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave_panic_ams_slave_panic_slave_id_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave_panic_ams_slave_panic_slave_id_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_ams_slave_panic_ams_slave_panic_kind_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_slave_panic_ams_slave_panic_kind_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave_panic_ams_slave_panic_kind_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint32_t can1__main_ft24_ams_slave_panic_ams_slave_panic_arg_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_ams_slave_panic_ams_slave_panic_arg_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_slave_panic_ams_slave_panic_arg_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_ams_in_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_ams_in_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->ts_activate, 0u, 0x01u);
+ dst_p[0] |= pack_left_shift_u8(src_p->inverters_discharged, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->lap_number, 2u, 0xfcu);
+
+ return (1);
+}
+
+int can1__main_ft24_ams_in_unpack(
+ struct can1__main_ft24_ams_in_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->ts_activate = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
+ dst_p->inverters_discharged = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->lap_number = unpack_right_shift_u8(src_p[0], 2u, 0xfcu);
+
+ return (0);
+}
+
+int can1__main_ft24_ams_in_init(struct can1__main_ft24_ams_in_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_ams_in_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_ams_in_ts_activate_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_in_ts_activate_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_in_ts_activate_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_in_inverters_discharged_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_in_inverters_discharged_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_in_inverters_discharged_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_ams_in_lap_number_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_ams_in_lap_number_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_ams_in_lap_number_is_in_range(uint8_t value)
+{
+ return (value <= 64u);
+}
+
+int can1__main_ft24_shunt_current_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_current_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_current;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ shunt_current = (uint32_t)src_p->shunt_current;
+ dst_p[2] |= pack_right_shift_u32(shunt_current, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(shunt_current, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(shunt_current, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(shunt_current, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_shunt_current_unpack(
+ struct can1__main_ft24_shunt_current_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_current;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ shunt_current = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ shunt_current |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ shunt_current |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ shunt_current |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+ dst_p->shunt_current = (int32_t)shunt_current;
+
+ return (0);
+}
+
+int can1__main_ft24_shunt_current_init(struct can1__main_ft24_shunt_current_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_shunt_current_t));
+
+ return 0;
+}
+
+int32_t can1__main_ft24_shunt_current_shunt_current_encode(double value)
+{
+ return (int32_t)(value / 0.001);
+}
+
+double can1__main_ft24_shunt_current_shunt_current_decode(int32_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_shunt_current_shunt_current_is_in_range(int32_t value)
+{
+ return ((value >= -2000000000) && (value <= 2000000000));
+}
+
+int can1__main_ft24_shunt_voltage1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_voltage1_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_voltage1;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ shunt_voltage1 = (uint32_t)src_p->shunt_voltage1;
+ dst_p[2] |= pack_right_shift_u32(shunt_voltage1, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(shunt_voltage1, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(shunt_voltage1, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(shunt_voltage1, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_shunt_voltage1_unpack(
+ struct can1__main_ft24_shunt_voltage1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_voltage1;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ shunt_voltage1 = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ shunt_voltage1 |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ shunt_voltage1 |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ shunt_voltage1 |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+ dst_p->shunt_voltage1 = (int32_t)shunt_voltage1;
+
+ return (0);
+}
+
+int can1__main_ft24_shunt_voltage1_init(struct can1__main_ft24_shunt_voltage1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_shunt_voltage1_t));
+
+ return 0;
+}
+
+int32_t can1__main_ft24_shunt_voltage1_shunt_voltage1_encode(double value)
+{
+ return (int32_t)(value / 0.001);
+}
+
+double can1__main_ft24_shunt_voltage1_shunt_voltage1_decode(int32_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_shunt_voltage1_shunt_voltage1_is_in_range(int32_t value)
+{
+ return ((value >= -2000000000) && (value <= 2000000000));
+}
+
+int can1__main_ft24_shunt_voltage2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_voltage2_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_voltage2;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ shunt_voltage2 = (uint32_t)src_p->shunt_voltage2;
+ dst_p[2] |= pack_right_shift_u32(shunt_voltage2, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(shunt_voltage2, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(shunt_voltage2, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(shunt_voltage2, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_shunt_voltage2_unpack(
+ struct can1__main_ft24_shunt_voltage2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_voltage2;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ shunt_voltage2 = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ shunt_voltage2 |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ shunt_voltage2 |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ shunt_voltage2 |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+ dst_p->shunt_voltage2 = (int32_t)shunt_voltage2;
+
+ return (0);
+}
+
+int can1__main_ft24_shunt_voltage2_init(struct can1__main_ft24_shunt_voltage2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_shunt_voltage2_t));
+
+ return 0;
+}
+
+int32_t can1__main_ft24_shunt_voltage2_shunt_voltage2_encode(double value)
+{
+ return (int32_t)(value / 0.001);
+}
+
+double can1__main_ft24_shunt_voltage2_shunt_voltage2_decode(int32_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_shunt_voltage2_shunt_voltage2_is_in_range(int32_t value)
+{
+ return ((value >= -2000000000) && (value <= 2000000000));
+}
+
+int can1__main_ft24_shunt_voltage3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_voltage3_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_voltage3;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ shunt_voltage3 = (uint32_t)src_p->shunt_voltage3;
+ dst_p[2] |= pack_right_shift_u32(shunt_voltage3, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(shunt_voltage3, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(shunt_voltage3, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(shunt_voltage3, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_shunt_voltage3_unpack(
+ struct can1__main_ft24_shunt_voltage3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint32_t shunt_voltage3;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ shunt_voltage3 = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ shunt_voltage3 |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ shunt_voltage3 |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ shunt_voltage3 |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+ dst_p->shunt_voltage3 = (int32_t)shunt_voltage3;
+
+ return (0);
+}
+
+int can1__main_ft24_shunt_voltage3_init(struct can1__main_ft24_shunt_voltage3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_shunt_voltage3_t));
+
+ return 0;
+}
+
+int32_t can1__main_ft24_shunt_voltage3_shunt_voltage3_encode(double value)
+{
+ return (int32_t)(value / 0.001);
+}
+
+double can1__main_ft24_shunt_voltage3_shunt_voltage3_decode(int32_t value)
+{
+ return ((double)value * 0.001);
+}
+
+bool can1__main_ft24_shunt_voltage3_shunt_voltage3_is_in_range(int32_t value)
+{
+ return ((value >= -2000000000) && (value <= 2000000000));
+}
+
+int can1__main_ft24_shunt_temperature_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_shunt_temperature_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[2] |= pack_right_shift_u32(src_p->shunt_temperature, 24u, 0xffu);
+ dst_p[3] |= pack_right_shift_u32(src_p->shunt_temperature, 16u, 0xffu);
+ dst_p[4] |= pack_right_shift_u32(src_p->shunt_temperature, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u32(src_p->shunt_temperature, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_shunt_temperature_unpack(
+ struct can1__main_ft24_shunt_temperature_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->shunt_temperature = unpack_left_shift_u32(src_p[2], 24u, 0xffu);
+ dst_p->shunt_temperature |= unpack_left_shift_u32(src_p[3], 16u, 0xffu);
+ dst_p->shunt_temperature |= unpack_left_shift_u32(src_p[4], 8u, 0xffu);
+ dst_p->shunt_temperature |= unpack_right_shift_u32(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_shunt_temperature_init(struct can1__main_ft24_shunt_temperature_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_shunt_temperature_t));
+
+ return 0;
+}
+
+uint32_t can1__main_ft24_shunt_temperature_shunt_temperature_encode(double value)
+{
+ return (uint32_t)(value / 0.1);
+}
+
+double can1__main_ft24_shunt_temperature_shunt_temperature_decode(uint32_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_shunt_temperature_shunt_temperature_is_in_range(uint32_t value)
+{
+ return (value <= 10000u);
+}
+
+int can1__main_ft24_sdcl_tx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_sdcl_tx_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 4);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->asms_state, 0u, 0x01u);
+ dst_p[0] |= pack_left_shift_u8(src_p->sdc_state_1, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->sdc_state_2, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->sdc_state_3, 3u, 0x08u);
+ dst_p[0] |= pack_left_shift_u8(src_p->heartbeat_ok, 4u, 0x10u);
+ dst_p[0] |= pack_left_shift_u8(src_p->sdcl_sdc_ready, 5u, 0x20u);
+ dst_p[0] |= pack_left_shift_u8(src_p->ts_start_muxed, 6u, 0x40u);
+ dst_p[1] |= pack_left_shift_u8(src_p->latch_init_open, 0u, 0x01u);
+ dst_p[1] |= pack_left_shift_u8(src_p->latch_closed, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->latch_reopened, 2u, 0x04u);
+ dst_p[1] |= pack_left_shift_u8(src_p->as_mission, 3u, 0x38u);
+
+ return (4);
+}
+
+int can1__main_ft24_sdcl_tx_unpack(
+ struct can1__main_ft24_sdcl_tx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ dst_p->asms_state = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
+ dst_p->sdc_state_1 = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->sdc_state_2 = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->sdc_state_3 = unpack_right_shift_u8(src_p[0], 3u, 0x08u);
+ dst_p->heartbeat_ok = unpack_right_shift_u8(src_p[0], 4u, 0x10u);
+ dst_p->sdcl_sdc_ready = unpack_right_shift_u8(src_p[0], 5u, 0x20u);
+ dst_p->ts_start_muxed = unpack_right_shift_u8(src_p[0], 6u, 0x40u);
+ dst_p->latch_init_open = unpack_right_shift_u8(src_p[1], 0u, 0x01u);
+ dst_p->latch_closed = unpack_right_shift_u8(src_p[1], 1u, 0x02u);
+ dst_p->latch_reopened = unpack_right_shift_u8(src_p[1], 2u, 0x04u);
+ dst_p->as_mission = unpack_right_shift_u8(src_p[1], 3u, 0x38u);
+
+ return (0);
+}
+
+int can1__main_ft24_sdcl_tx_init(struct can1__main_ft24_sdcl_tx_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_sdcl_tx_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_sdcl_tx_asms_state_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_asms_state_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_asms_state_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_sdc_state_1_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_sdc_state_1_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_sdc_state_1_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_sdc_state_2_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_sdc_state_2_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_sdc_state_2_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_sdc_state_3_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_sdc_state_3_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_sdc_state_3_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_heartbeat_ok_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_heartbeat_ok_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_heartbeat_ok_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_sdcl_sdc_ready_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_sdcl_sdc_ready_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_sdcl_sdc_ready_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_ts_start_muxed_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_ts_start_muxed_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_ts_start_muxed_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_latch_init_open_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_latch_init_open_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_latch_init_open_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_latch_closed_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_latch_closed_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_latch_closed_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_latch_reopened_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_latch_reopened_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_latch_reopened_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_tx_as_mission_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_tx_as_mission_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_tx_as_mission_is_in_range(uint8_t value)
+{
+ return (value <= 7u);
+}
+
+int can1__main_ft24_sdcl_rx_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_sdcl_rx_t *src_p,
+ size_t size)
+{
+ if (size < 3u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 3);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->as_close_sdc, 0u, 0x01u);
+ dst_p[0] |= pack_left_shift_u8(src_p->sdcl_heartbeat, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->asb_error, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->as_mission, 4u, 0x70u);
+
+ return (3);
+}
+
+int can1__main_ft24_sdcl_rx_unpack(
+ struct can1__main_ft24_sdcl_rx_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 3u) {
+ return (-EINVAL);
+ }
+
+ dst_p->as_close_sdc = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
+ dst_p->sdcl_heartbeat = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->asb_error = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->as_mission = unpack_right_shift_u8(src_p[0], 4u, 0x70u);
+
+ return (0);
+}
+
+int can1__main_ft24_sdcl_rx_init(struct can1__main_ft24_sdcl_rx_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_sdcl_rx_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_sdcl_rx_as_close_sdc_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_rx_as_close_sdc_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_rx_as_close_sdc_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_rx_sdcl_heartbeat_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_rx_sdcl_heartbeat_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_rx_sdcl_heartbeat_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_rx_asb_error_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_rx_asb_error_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_rx_asb_error_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_sdcl_rx_as_mission_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_sdcl_rx_as_mission_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_sdcl_rx_as_mission_is_in_range(uint8_t value)
+{
+ return (value <= 7u);
+}
+
+int can1__main_ft24_pdu_command_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_command_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_inverter_rx, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_mode_valve_2_rx, 6u, 0x40u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_ebs_valve_2_rx, 5u, 0x20u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_shutdown_circuit_rx, 4u, 0x10u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_alwayson_rx, 3u, 0x08u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_misc_rx, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_servo_rx, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_led1_rx, 7u, 0x80u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_led2_rx, 6u, 0x40u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_led3_rx, 5u, 0x20u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_sensorbox_rx, 4u, 0x10u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_service_brake_rx, 3u, 0x08u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_ebs_valve_1_rx, 2u, 0x04u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_steering_rx, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_mode_valve_1_rx, 0u, 0x01u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdu_pwm_fans_rx, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->pdu_pwm_aggregat_rx, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->pdu_pwm_pump_rx, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->pdu_checksum_rx, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_pdu_command_unpack(
+ struct can1__main_ft24_pdu_command_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdu_inverter_rx = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->pdu_mode_valve_2_rx = unpack_right_shift_u8(src_p[0], 6u, 0x40u);
+ dst_p->pdu_ebs_valve_2_rx = unpack_right_shift_u8(src_p[0], 5u, 0x20u);
+ dst_p->pdu_shutdown_circuit_rx = unpack_right_shift_u8(src_p[0], 4u, 0x10u);
+ dst_p->pdu_alwayson_rx = unpack_right_shift_u8(src_p[0], 3u, 0x08u);
+ dst_p->pdu_misc_rx = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->pdu_servo_rx = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->pdu_led1_rx = unpack_right_shift_u8(src_p[1], 7u, 0x80u);
+ dst_p->pdu_led2_rx = unpack_right_shift_u8(src_p[1], 6u, 0x40u);
+ dst_p->pdu_led3_rx = unpack_right_shift_u8(src_p[1], 5u, 0x20u);
+ dst_p->pdu_sensorbox_rx = unpack_right_shift_u8(src_p[1], 4u, 0x10u);
+ dst_p->pdu_service_brake_rx = unpack_right_shift_u8(src_p[1], 3u, 0x08u);
+ dst_p->pdu_ebs_valve_1_rx = unpack_right_shift_u8(src_p[1], 2u, 0x04u);
+ dst_p->pdu_steering_rx = unpack_right_shift_u8(src_p[1], 1u, 0x02u);
+ dst_p->pdu_mode_valve_1_rx = unpack_right_shift_u8(src_p[1], 0u, 0x01u);
+ dst_p->pdu_pwm_fans_rx = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->pdu_pwm_aggregat_rx = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->pdu_pwm_pump_rx = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->pdu_checksum_rx = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_pdu_command_init(struct can1__main_ft24_pdu_command_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_pdu_command_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_inverter_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_inverter_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_inverter_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_mode_valve_2_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_mode_valve_2_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_mode_valve_2_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_ebs_valve_2_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_ebs_valve_2_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_ebs_valve_2_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_shutdown_circuit_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_shutdown_circuit_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_shutdown_circuit_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_alwayson_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_alwayson_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_alwayson_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_misc_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_misc_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_misc_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_servo_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_servo_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_servo_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_led1_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_led1_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_led1_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_led2_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_led2_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_led2_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_led3_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_led3_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_led3_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_sensorbox_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_sensorbox_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_sensorbox_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_service_brake_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_service_brake_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_service_brake_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_ebs_valve_1_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_ebs_valve_1_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_ebs_valve_1_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_steering_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_steering_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_steering_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_mode_valve_1_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_mode_valve_1_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_mode_valve_1_rx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_pwm_fans_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_pwm_fans_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_pwm_fans_rx_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_pwm_aggregat_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_pwm_aggregat_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_pwm_aggregat_rx_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_pwm_pump_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_pwm_pump_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_pwm_pump_rx_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_pdu_command_pdu_checksum_rx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_command_pdu_checksum_rx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_command_pdu_checksum_rx_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_pdu_response_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_response_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_inverter_tx, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_mode_valve_2_tx, 6u, 0x40u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_evs_valve_2_tx, 5u, 0x20u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_shutdown_circuit_tx, 4u, 0x10u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_alwayson_tx, 3u, 0x08u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_misc_tx, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdu_servo_tx, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_led1_tx, 7u, 0x80u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_led2_tx, 6u, 0x40u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_led3_tx, 5u, 0x20u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_sensorbox_tx, 4u, 0x10u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_service_brake_tx, 3u, 0x08u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_ebs_valve_1_tx, 2u, 0x04u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_steering_tx, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdu_mode_valve_1_tx, 0u, 0x01u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdu_pwm_fans_tx, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->pdu_pwm_aggregat, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->pdu_pwm_pump, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->pdu_checksum_tx, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_pdu_response_unpack(
+ struct can1__main_ft24_pdu_response_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdu_inverter_tx = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+ dst_p->pdu_mode_valve_2_tx = unpack_right_shift_u8(src_p[0], 6u, 0x40u);
+ dst_p->pdu_evs_valve_2_tx = unpack_right_shift_u8(src_p[0], 5u, 0x20u);
+ dst_p->pdu_shutdown_circuit_tx = unpack_right_shift_u8(src_p[0], 4u, 0x10u);
+ dst_p->pdu_alwayson_tx = unpack_right_shift_u8(src_p[0], 3u, 0x08u);
+ dst_p->pdu_misc_tx = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->pdu_servo_tx = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->pdu_led1_tx = unpack_right_shift_u8(src_p[1], 7u, 0x80u);
+ dst_p->pdu_led2_tx = unpack_right_shift_u8(src_p[1], 6u, 0x40u);
+ dst_p->pdu_led3_tx = unpack_right_shift_u8(src_p[1], 5u, 0x20u);
+ dst_p->pdu_sensorbox_tx = unpack_right_shift_u8(src_p[1], 4u, 0x10u);
+ dst_p->pdu_service_brake_tx = unpack_right_shift_u8(src_p[1], 3u, 0x08u);
+ dst_p->pdu_ebs_valve_1_tx = unpack_right_shift_u8(src_p[1], 2u, 0x04u);
+ dst_p->pdu_steering_tx = unpack_right_shift_u8(src_p[1], 1u, 0x02u);
+ dst_p->pdu_mode_valve_1_tx = unpack_right_shift_u8(src_p[1], 0u, 0x01u);
+ dst_p->pdu_pwm_fans_tx = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->pdu_pwm_aggregat = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->pdu_pwm_pump = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->pdu_checksum_tx = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_pdu_response_init(struct can1__main_ft24_pdu_response_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_pdu_response_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_inverter_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_inverter_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_inverter_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_mode_valve_2_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_mode_valve_2_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_mode_valve_2_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_evs_valve_2_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_evs_valve_2_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_evs_valve_2_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_shutdown_circuit_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_shutdown_circuit_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_shutdown_circuit_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_alwayson_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_alwayson_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_alwayson_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_misc_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_misc_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_misc_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_servo_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_servo_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_servo_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_led1_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_led1_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_led1_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_led2_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_led2_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_led2_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_led3_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_led3_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_led3_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_sensorbox_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_sensorbox_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_sensorbox_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_service_brake_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_service_brake_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_service_brake_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_ebs_valve_1_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_ebs_valve_1_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_ebs_valve_1_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_steering_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_steering_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_steering_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_mode_valve_1_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_mode_valve_1_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_mode_valve_1_tx_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_pwm_fans_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_pwm_fans_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_pwm_fans_tx_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_pwm_aggregat_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_pwm_aggregat_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_pwm_aggregat_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_pwm_pump_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_pwm_pump_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_pwm_pump_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_pdu_response_pdu_checksum_tx_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_pdu_response_pdu_checksum_tx_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_response_pdu_checksum_tx_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_tx_pdo_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_tx_pdo_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->pdm_powersupply_less_8v, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdm_powersupply_greater_32v, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdm_canbus_timeout, 3u, 0x08u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdm_canbus_startupmissing, 4u, 0x10u);
+ dst_p[0] |= pack_left_shift_u8(src_p->pdm_canbus_statewarning, 5u, 0x20u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdm_analoginput_middleposition, 0u, 0x01u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdm_analoginput_cablebreak, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdm_analoginput_shortcircuit, 2u, 0x04u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdm_analoginput_currentoverload, 3u, 0x08u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdm_temperature_warning, 4u, 0x10u);
+ dst_p[1] |= pack_left_shift_u8(src_p->pdm_temperature_shutdown, 5u, 0x20u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdm_output1_controllerrange, 0u, 0x01u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdm_output2_controllerrange, 1u, 0x02u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdm_output1_cablebreak, 2u, 0x04u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdm_output2_cablebreak, 3u, 0x08u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdm_output1_shortcircuit, 4u, 0x10u);
+ dst_p[2] |= pack_left_shift_u8(src_p->pdm_output2_shortcircuit, 5u, 0x20u);
+ dst_p[4] |= pack_left_shift_u16(src_p->pdm_analoginput, 0u, 0xffu);
+ dst_p[5] |= pack_right_shift_u16(src_p->pdm_analoginput, 8u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_tx_pdo_unpack(
+ struct can1__main_ft24_tx_pdo_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdm_powersupply_less_8v = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->pdm_powersupply_greater_32v = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->pdm_canbus_timeout = unpack_right_shift_u8(src_p[0], 3u, 0x08u);
+ dst_p->pdm_canbus_startupmissing = unpack_right_shift_u8(src_p[0], 4u, 0x10u);
+ dst_p->pdm_canbus_statewarning = unpack_right_shift_u8(src_p[0], 5u, 0x20u);
+ dst_p->pdm_analoginput_middleposition = unpack_right_shift_u8(src_p[1], 0u, 0x01u);
+ dst_p->pdm_analoginput_cablebreak = unpack_right_shift_u8(src_p[1], 1u, 0x02u);
+ dst_p->pdm_analoginput_shortcircuit = unpack_right_shift_u8(src_p[1], 2u, 0x04u);
+ dst_p->pdm_analoginput_currentoverload = unpack_right_shift_u8(src_p[1], 3u, 0x08u);
+ dst_p->pdm_temperature_warning = unpack_right_shift_u8(src_p[1], 4u, 0x10u);
+ dst_p->pdm_temperature_shutdown = unpack_right_shift_u8(src_p[1], 5u, 0x20u);
+ dst_p->pdm_output1_controllerrange = unpack_right_shift_u8(src_p[2], 0u, 0x01u);
+ dst_p->pdm_output2_controllerrange = unpack_right_shift_u8(src_p[2], 1u, 0x02u);
+ dst_p->pdm_output1_cablebreak = unpack_right_shift_u8(src_p[2], 2u, 0x04u);
+ dst_p->pdm_output2_cablebreak = unpack_right_shift_u8(src_p[2], 3u, 0x08u);
+ dst_p->pdm_output1_shortcircuit = unpack_right_shift_u8(src_p[2], 4u, 0x10u);
+ dst_p->pdm_output2_shortcircuit = unpack_right_shift_u8(src_p[2], 5u, 0x20u);
+ dst_p->pdm_analoginput = unpack_right_shift_u16(src_p[4], 0u, 0xffu);
+ dst_p->pdm_analoginput |= unpack_left_shift_u16(src_p[5], 8u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_tx_pdo_init(struct can1__main_ft24_tx_pdo_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_tx_pdo_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_powersupply_less_8v_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_powersupply_less_8v_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_powersupply_less_8v_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_powersupply_greater_32v_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_powersupply_greater_32v_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_powersupply_greater_32v_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_canbus_timeout_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_canbus_timeout_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_canbus_timeout_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_canbus_startupmissing_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_canbus_startupmissing_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_canbus_startupmissing_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_canbus_statewarning_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_canbus_statewarning_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_canbus_statewarning_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_middleposition_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_analoginput_middleposition_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_analoginput_middleposition_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_cablebreak_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_analoginput_cablebreak_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_analoginput_cablebreak_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_shortcircuit_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_analoginput_shortcircuit_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_analoginput_shortcircuit_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_analoginput_currentoverload_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_analoginput_currentoverload_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_analoginput_currentoverload_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_temperature_warning_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_temperature_warning_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_temperature_warning_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_temperature_shutdown_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_temperature_shutdown_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_temperature_shutdown_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_output1_controllerrange_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_output1_controllerrange_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_output1_controllerrange_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_output2_controllerrange_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_output2_controllerrange_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_output2_controllerrange_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_output1_cablebreak_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_output1_cablebreak_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_output1_cablebreak_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_output2_cablebreak_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_output2_cablebreak_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_output2_cablebreak_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_output1_shortcircuit_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_output1_shortcircuit_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_output1_shortcircuit_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_tx_pdo_pdm_output2_shortcircuit_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_output2_shortcircuit_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_output2_shortcircuit_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint16_t can1__main_ft24_tx_pdo_pdm_analoginput_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_tx_pdo_pdm_analoginput_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_tx_pdo_pdm_analoginput_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_x_sens_error_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_error_t *src_p,
+ size_t size)
+{
+ (void)src_p;
+
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ return (1);
+}
+
+int can1__main_ft24_x_sens_error_unpack(
+ struct can1__main_ft24_x_sens_error_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ (void)dst_p;
+ (void)src_p;
+
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_error_init(struct can1__main_ft24_x_sens_error_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_error_t));
+
+ return 0;
+}
+
+int can1__main_ft24_x_sens_warning_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_warning_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->warning_code, 0u, 0xffu);
+
+ return (1);
+}
+
+int can1__main_ft24_x_sens_warning_unpack(
+ struct can1__main_ft24_x_sens_warning_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->warning_code = unpack_right_shift_u8(src_p[0], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_warning_init(struct can1__main_ft24_x_sens_warning_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_warning_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_x_sens_warning_warning_code_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_warning_warning_code_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_warning_warning_code_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_x_sens_sample_time_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_sample_time_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 4);
+
+ dst_p[0] |= pack_right_shift_u32(src_p->timestamp, 24u, 0xffu);
+ dst_p[1] |= pack_right_shift_u32(src_p->timestamp, 16u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(src_p->timestamp, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u32(src_p->timestamp, 0u, 0xffu);
+
+ return (4);
+}
+
+int can1__main_ft24_x_sens_sample_time_unpack(
+ struct can1__main_ft24_x_sens_sample_time_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ dst_p->timestamp = unpack_left_shift_u32(src_p[0], 24u, 0xffu);
+ dst_p->timestamp |= unpack_left_shift_u32(src_p[1], 16u, 0xffu);
+ dst_p->timestamp |= unpack_left_shift_u32(src_p[2], 8u, 0xffu);
+ dst_p->timestamp |= unpack_right_shift_u32(src_p[3], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_sample_time_init(struct can1__main_ft24_x_sens_sample_time_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_sample_time_t));
+
+ return 0;
+}
+
+uint32_t can1__main_ft24_x_sens_sample_time_timestamp_encode(double value)
+{
+ return (uint32_t)(value);
+}
+
+double can1__main_ft24_x_sens_sample_time_timestamp_decode(uint32_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_sample_time_timestamp_is_in_range(uint32_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_x_sens_group_counter_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_group_counter_t *src_p,
+ size_t size)
+{
+ if (size < 2u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 2);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->counter, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->counter, 0u, 0xffu);
+
+ return (2);
+}
+
+int can1__main_ft24_x_sens_group_counter_unpack(
+ struct can1__main_ft24_x_sens_group_counter_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 2u) {
+ return (-EINVAL);
+ }
+
+ dst_p->counter = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->counter |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_group_counter_init(struct can1__main_ft24_x_sens_group_counter_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_group_counter_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_x_sens_group_counter_counter_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_x_sens_group_counter_counter_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_group_counter_counter_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_x_sens_status_word_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_status_word_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 4);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->have_gnss_time_pulse, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->rtk_status, 3u, 0x18u);
+ dst_p[0] |= pack_right_shift_u8(src_p->filter_mode, 1u, 0x03u);
+ dst_p[1] |= pack_left_shift_u8(src_p->filter_mode, 7u, 0x80u);
+ dst_p[1] |= pack_left_shift_u8(src_p->clip_mag_z, 0u, 0x01u);
+ dst_p[1] |= pack_left_shift_u8(src_p->retransmitted, 2u, 0x04u);
+ dst_p[1] |= pack_left_shift_u8(src_p->clipping_detected, 3u, 0x08u);
+ dst_p[1] |= pack_left_shift_u8(src_p->interpolated, 4u, 0x10u);
+ dst_p[1] |= pack_left_shift_u8(src_p->sync_in, 5u, 0x20u);
+ dst_p[1] |= pack_left_shift_u8(src_p->sync_out, 6u, 0x40u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_acc_x, 0u, 0x01u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_acc_y, 1u, 0x02u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_acc_z, 2u, 0x04u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_gyr_x, 3u, 0x08u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_gyr_y, 4u, 0x10u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_gyr_z, 5u, 0x20u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_mag_x, 6u, 0x40u);
+ dst_p[2] |= pack_left_shift_u8(src_p->clip_mag_y, 7u, 0x80u);
+ dst_p[3] |= pack_left_shift_u8(src_p->self_test_ok, 0u, 0x01u);
+ dst_p[3] |= pack_left_shift_u8(src_p->orientation_valid, 1u, 0x02u);
+ dst_p[3] |= pack_left_shift_u8(src_p->gps_valid, 2u, 0x04u);
+ dst_p[3] |= pack_left_shift_u8(src_p->no_rotation, 3u, 0x18u);
+ dst_p[3] |= pack_left_shift_u8(src_p->representative_motion, 5u, 0x20u);
+ dst_p[3] |= pack_left_shift_u8(src_p->external_clock_synced, 6u, 0x40u);
+
+ return (4);
+}
+
+int can1__main_ft24_x_sens_status_word_unpack(
+ struct can1__main_ft24_x_sens_status_word_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 4u) {
+ return (-EINVAL);
+ }
+
+ dst_p->have_gnss_time_pulse = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->rtk_status = unpack_right_shift_u8(src_p[0], 3u, 0x18u);
+ dst_p->filter_mode = unpack_left_shift_u8(src_p[0], 1u, 0x03u);
+ dst_p->filter_mode |= unpack_right_shift_u8(src_p[1], 7u, 0x80u);
+ dst_p->clip_mag_z = unpack_right_shift_u8(src_p[1], 0u, 0x01u);
+ dst_p->retransmitted = unpack_right_shift_u8(src_p[1], 2u, 0x04u);
+ dst_p->clipping_detected = unpack_right_shift_u8(src_p[1], 3u, 0x08u);
+ dst_p->interpolated = unpack_right_shift_u8(src_p[1], 4u, 0x10u);
+ dst_p->sync_in = unpack_right_shift_u8(src_p[1], 5u, 0x20u);
+ dst_p->sync_out = unpack_right_shift_u8(src_p[1], 6u, 0x40u);
+ dst_p->clip_acc_x = unpack_right_shift_u8(src_p[2], 0u, 0x01u);
+ dst_p->clip_acc_y = unpack_right_shift_u8(src_p[2], 1u, 0x02u);
+ dst_p->clip_acc_z = unpack_right_shift_u8(src_p[2], 2u, 0x04u);
+ dst_p->clip_gyr_x = unpack_right_shift_u8(src_p[2], 3u, 0x08u);
+ dst_p->clip_gyr_y = unpack_right_shift_u8(src_p[2], 4u, 0x10u);
+ dst_p->clip_gyr_z = unpack_right_shift_u8(src_p[2], 5u, 0x20u);
+ dst_p->clip_mag_x = unpack_right_shift_u8(src_p[2], 6u, 0x40u);
+ dst_p->clip_mag_y = unpack_right_shift_u8(src_p[2], 7u, 0x80u);
+ dst_p->self_test_ok = unpack_right_shift_u8(src_p[3], 0u, 0x01u);
+ dst_p->orientation_valid = unpack_right_shift_u8(src_p[3], 1u, 0x02u);
+ dst_p->gps_valid = unpack_right_shift_u8(src_p[3], 2u, 0x04u);
+ dst_p->no_rotation = unpack_right_shift_u8(src_p[3], 3u, 0x18u);
+ dst_p->representative_motion = unpack_right_shift_u8(src_p[3], 5u, 0x20u);
+ dst_p->external_clock_synced = unpack_right_shift_u8(src_p[3], 6u, 0x40u);
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_status_word_init(struct can1__main_ft24_x_sens_status_word_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_status_word_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_have_gnss_time_pulse_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_have_gnss_time_pulse_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_have_gnss_time_pulse_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_rtk_status_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_rtk_status_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_rtk_status_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_filter_mode_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_filter_mode_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_filter_mode_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_mag_z_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_mag_z_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_mag_z_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_retransmitted_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_retransmitted_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_retransmitted_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clipping_detected_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clipping_detected_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clipping_detected_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_interpolated_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_interpolated_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_interpolated_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_sync_in_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_sync_in_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_sync_in_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_sync_out_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_sync_out_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_sync_out_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_acc_x_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_acc_x_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_acc_x_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_acc_y_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_acc_y_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_acc_y_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_acc_z_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_acc_z_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_acc_z_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_gyr_x_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_gyr_x_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_gyr_x_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_gyr_y_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_gyr_y_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_gyr_y_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_gyr_z_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_gyr_z_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_gyr_z_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_mag_x_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_mag_x_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_mag_x_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_clip_mag_y_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_clip_mag_y_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_clip_mag_y_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_self_test_ok_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_self_test_ok_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_self_test_ok_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_orientation_valid_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_orientation_valid_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_orientation_valid_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_gps_valid_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_gps_valid_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_gps_valid_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_no_rotation_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_no_rotation_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_no_rotation_is_in_range(uint8_t value)
+{
+ return (value <= 3u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_representative_motion_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_representative_motion_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_representative_motion_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_x_sens_status_word_external_clock_synced_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_x_sens_status_word_external_clock_synced_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_x_sens_status_word_external_clock_synced_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+int can1__main_ft24_x_sens_rate_of_turn_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_rate_of_turn_t *src_p,
+ size_t size)
+{
+ uint16_t x_sens_gyr_x;
+ uint16_t x_sens_gyr_y;
+ uint16_t x_sens_gyr_z;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ x_sens_gyr_x = (uint16_t)src_p->x_sens_gyr_x;
+ dst_p[0] |= pack_right_shift_u16(x_sens_gyr_x, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(x_sens_gyr_x, 0u, 0xffu);
+ x_sens_gyr_y = (uint16_t)src_p->x_sens_gyr_y;
+ dst_p[2] |= pack_right_shift_u16(x_sens_gyr_y, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(x_sens_gyr_y, 0u, 0xffu);
+ x_sens_gyr_z = (uint16_t)src_p->x_sens_gyr_z;
+ dst_p[4] |= pack_right_shift_u16(x_sens_gyr_z, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(x_sens_gyr_z, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_x_sens_rate_of_turn_unpack(
+ struct can1__main_ft24_x_sens_rate_of_turn_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t x_sens_gyr_x;
+ uint16_t x_sens_gyr_y;
+ uint16_t x_sens_gyr_z;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ x_sens_gyr_x = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ x_sens_gyr_x |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->x_sens_gyr_x = (int16_t)x_sens_gyr_x;
+ x_sens_gyr_y = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ x_sens_gyr_y |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->x_sens_gyr_y = (int16_t)x_sens_gyr_y;
+ x_sens_gyr_z = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ x_sens_gyr_z |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->x_sens_gyr_z = (int16_t)x_sens_gyr_z;
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_rate_of_turn_init(struct can1__main_ft24_x_sens_rate_of_turn_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_rate_of_turn_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_x_encode(double value)
+{
+ return (int16_t)(value / 0.00195313);
+}
+
+double can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_x_decode(int16_t value)
+{
+ return ((double)value * 0.00195313);
+}
+
+bool can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_x_is_in_range(int16_t value)
+{
+ return ((value >= -17920) && (value <= 17920));
+}
+
+int16_t can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_y_encode(double value)
+{
+ return (int16_t)(value / 0.00195313);
+}
+
+double can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_y_decode(int16_t value)
+{
+ return ((double)value * 0.00195313);
+}
+
+bool can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_y_is_in_range(int16_t value)
+{
+ return ((value >= -17920) && (value <= 17920));
+}
+
+int16_t can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_z_encode(double value)
+{
+ return (int16_t)(value / 0.00195313);
+}
+
+double can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_z_decode(int16_t value)
+{
+ return ((double)value * 0.00195313);
+}
+
+bool can1__main_ft24_x_sens_rate_of_turn_x_sens_gyr_z_is_in_range(int16_t value)
+{
+ return ((value >= -17920) && (value <= 17920));
+}
+
+int can1__main_ft24_x_sens_acceleration_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_acceleration_t *src_p,
+ size_t size)
+{
+ uint16_t x_sens_acc_x;
+ uint16_t x_sens_acc_y;
+ uint16_t x_sens_acc_z;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ x_sens_acc_x = (uint16_t)src_p->x_sens_acc_x;
+ dst_p[0] |= pack_right_shift_u16(x_sens_acc_x, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(x_sens_acc_x, 0u, 0xffu);
+ x_sens_acc_y = (uint16_t)src_p->x_sens_acc_y;
+ dst_p[2] |= pack_right_shift_u16(x_sens_acc_y, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(x_sens_acc_y, 0u, 0xffu);
+ x_sens_acc_z = (uint16_t)src_p->x_sens_acc_z;
+ dst_p[4] |= pack_right_shift_u16(x_sens_acc_z, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(x_sens_acc_z, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_x_sens_acceleration_unpack(
+ struct can1__main_ft24_x_sens_acceleration_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t x_sens_acc_x;
+ uint16_t x_sens_acc_y;
+ uint16_t x_sens_acc_z;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ x_sens_acc_x = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ x_sens_acc_x |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->x_sens_acc_x = (int16_t)x_sens_acc_x;
+ x_sens_acc_y = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ x_sens_acc_y |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->x_sens_acc_y = (int16_t)x_sens_acc_y;
+ x_sens_acc_z = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ x_sens_acc_z |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->x_sens_acc_z = (int16_t)x_sens_acc_z;
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_acceleration_init(struct can1__main_ft24_x_sens_acceleration_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_acceleration_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_x_sens_acceleration_x_sens_acc_x_encode(double value)
+{
+ return (int16_t)(value / 0.00390625);
+}
+
+double can1__main_ft24_x_sens_acceleration_x_sens_acc_x_decode(int16_t value)
+{
+ return ((double)value * 0.00390625);
+}
+
+bool can1__main_ft24_x_sens_acceleration_x_sens_acc_x_is_in_range(int16_t value)
+{
+ return ((value >= -25600) && (value <= 25600));
+}
+
+int16_t can1__main_ft24_x_sens_acceleration_x_sens_acc_y_encode(double value)
+{
+ return (int16_t)(value / 0.00390625);
+}
+
+double can1__main_ft24_x_sens_acceleration_x_sens_acc_y_decode(int16_t value)
+{
+ return ((double)value * 0.00390625);
+}
+
+bool can1__main_ft24_x_sens_acceleration_x_sens_acc_y_is_in_range(int16_t value)
+{
+ return ((value >= -25600) && (value <= 25600));
+}
+
+int16_t can1__main_ft24_x_sens_acceleration_x_sens_acc_z_encode(double value)
+{
+ return (int16_t)(value / 0.00390625);
+}
+
+double can1__main_ft24_x_sens_acceleration_x_sens_acc_z_decode(int16_t value)
+{
+ return ((double)value * 0.00390625);
+}
+
+bool can1__main_ft24_x_sens_acceleration_x_sens_acc_z_is_in_range(int16_t value)
+{
+ return ((value >= -25600) && (value <= 25600));
+}
+
+int can1__main_ft24_x_sens_long_lat_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_long_lat_t *src_p,
+ size_t size)
+{
+ uint32_t latitude;
+ uint32_t longitude;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ latitude = (uint32_t)src_p->latitude;
+ dst_p[0] |= pack_right_shift_u32(latitude, 24u, 0xffu);
+ dst_p[1] |= pack_right_shift_u32(latitude, 16u, 0xffu);
+ dst_p[2] |= pack_right_shift_u32(latitude, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u32(latitude, 0u, 0xffu);
+ longitude = (uint32_t)src_p->longitude;
+ dst_p[4] |= pack_right_shift_u32(longitude, 24u, 0xffu);
+ dst_p[5] |= pack_right_shift_u32(longitude, 16u, 0xffu);
+ dst_p[6] |= pack_right_shift_u32(longitude, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u32(longitude, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_x_sens_long_lat_unpack(
+ struct can1__main_ft24_x_sens_long_lat_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint32_t latitude;
+ uint32_t longitude;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ latitude = unpack_left_shift_u32(src_p[0], 24u, 0xffu);
+ latitude |= unpack_left_shift_u32(src_p[1], 16u, 0xffu);
+ latitude |= unpack_left_shift_u32(src_p[2], 8u, 0xffu);
+ latitude |= unpack_right_shift_u32(src_p[3], 0u, 0xffu);
+ dst_p->latitude = (int32_t)latitude;
+ longitude = unpack_left_shift_u32(src_p[4], 24u, 0xffu);
+ longitude |= unpack_left_shift_u32(src_p[5], 16u, 0xffu);
+ longitude |= unpack_left_shift_u32(src_p[6], 8u, 0xffu);
+ longitude |= unpack_right_shift_u32(src_p[7], 0u, 0xffu);
+ dst_p->longitude = (int32_t)longitude;
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_long_lat_init(struct can1__main_ft24_x_sens_long_lat_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_long_lat_t));
+
+ return 0;
+}
+
+int32_t can1__main_ft24_x_sens_long_lat_latitude_encode(double value)
+{
+ return (int32_t)(value / 5.96046e-08);
+}
+
+double can1__main_ft24_x_sens_long_lat_latitude_decode(int32_t value)
+{
+ return ((double)value * 5.96046e-08);
+}
+
+bool can1__main_ft24_x_sens_long_lat_latitude_is_in_range(int32_t value)
+{
+ return ((value >= -1509950574) && (value <= 1509950574));
+}
+
+int32_t can1__main_ft24_x_sens_long_lat_longitude_encode(double value)
+{
+ return (int32_t)(value / 1.19209e-07);
+}
+
+double can1__main_ft24_x_sens_long_lat_longitude_decode(int32_t value)
+{
+ return ((double)value * 1.19209e-07);
+}
+
+bool can1__main_ft24_x_sens_long_lat_longitude_is_in_range(int32_t value)
+{
+ return ((value >= -1509953108) && (value <= 1509953108));
+}
+
+int can1__main_ft24_x_sens_velocity_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_x_sens_velocity_t *src_p,
+ size_t size)
+{
+ uint16_t vel_x;
+ uint16_t vel_y;
+ uint16_t vel_z;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ vel_x = (uint16_t)src_p->vel_x;
+ dst_p[0] |= pack_right_shift_u16(vel_x, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(vel_x, 0u, 0xffu);
+ vel_y = (uint16_t)src_p->vel_y;
+ dst_p[2] |= pack_right_shift_u16(vel_y, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(vel_y, 0u, 0xffu);
+ vel_z = (uint16_t)src_p->vel_z;
+ dst_p[4] |= pack_right_shift_u16(vel_z, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(vel_z, 0u, 0xffu);
+
+ return (6);
+}
+
+int can1__main_ft24_x_sens_velocity_unpack(
+ struct can1__main_ft24_x_sens_velocity_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t vel_x;
+ uint16_t vel_y;
+ uint16_t vel_z;
+
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ vel_x = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ vel_x |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->vel_x = (int16_t)vel_x;
+ vel_y = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ vel_y |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->vel_y = (int16_t)vel_y;
+ vel_z = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ vel_z |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->vel_z = (int16_t)vel_z;
+
+ return (0);
+}
+
+int can1__main_ft24_x_sens_velocity_init(struct can1__main_ft24_x_sens_velocity_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_x_sens_velocity_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_x_sens_velocity_vel_x_encode(double value)
+{
+ return (int16_t)(value / 0.015625);
+}
+
+double can1__main_ft24_x_sens_velocity_vel_x_decode(int16_t value)
+{
+ return ((double)value * 0.015625);
+}
+
+bool can1__main_ft24_x_sens_velocity_vel_x_is_in_range(int16_t value)
+{
+ return ((value >= -32000) && (value <= 32000));
+}
+
+int16_t can1__main_ft24_x_sens_velocity_vel_y_encode(double value)
+{
+ return (int16_t)(value / 0.015625);
+}
+
+double can1__main_ft24_x_sens_velocity_vel_y_decode(int16_t value)
+{
+ return ((double)value * 0.015625);
+}
+
+bool can1__main_ft24_x_sens_velocity_vel_y_is_in_range(int16_t value)
+{
+ return ((value >= -32000) && (value <= 32000));
+}
+
+int16_t can1__main_ft24_x_sens_velocity_vel_z_encode(double value)
+{
+ return (int16_t)(value / 0.015625);
+}
+
+double can1__main_ft24_x_sens_velocity_vel_z_decode(int16_t value)
+{
+ return ((double)value * 0.015625);
+}
+
+bool can1__main_ft24_x_sens_velocity_vel_z_is_in_range(int16_t value)
+{
+ return ((value >= -32000) && (value <= 32000));
+}
+
+int can1__main_ft24_as_mission_fb_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_as_mission_fb_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->mission_selection, 0u, 0x07u);
+
+ return (1);
+}
+
+int can1__main_ft24_as_mission_fb_unpack(
+ struct can1__main_ft24_as_mission_fb_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->mission_selection = unpack_right_shift_u8(src_p[0], 0u, 0x07u);
+
+ return (0);
+}
+
+int can1__main_ft24_as_mission_fb_init(struct can1__main_ft24_as_mission_fb_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_as_mission_fb_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_as_mission_fb_mission_selection_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_as_mission_fb_mission_selection_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_as_mission_fb_mission_selection_is_in_range(uint8_t value)
+{
+ return ((value >= 1u) && (value <= 7u));
+}
+
+int can1__main_ft24_stw_mission_selected_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_mission_selected_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->mission_selection, 0u, 0x07u);
+
+ return (1);
+}
+
+int can1__main_ft24_stw_mission_selected_unpack(
+ struct can1__main_ft24_stw_mission_selected_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->mission_selection = unpack_right_shift_u8(src_p[0], 0u, 0x07u);
+
+ return (0);
+}
+
+int can1__main_ft24_stw_mission_selected_init(struct can1__main_ft24_stw_mission_selected_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_stw_mission_selected_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_stw_mission_selected_mission_selection_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_mission_selected_mission_selection_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_mission_selected_mission_selection_is_in_range(uint8_t value)
+{
+ return ((value >= 1u) && (value <= 7u));
+}
+
+int can1__main_ft24_epsc_out_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_epsc_out_t *src_p,
+ size_t size)
+{
+ uint16_t epsc_measured_rpm;
+ uint16_t epsc_measured_steering_angle;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ epsc_measured_steering_angle = (uint16_t)src_p->epsc_measured_steering_angle;
+ dst_p[0] |= pack_right_shift_u16(epsc_measured_steering_angle, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(epsc_measured_steering_angle, 0u, 0xffu);
+ dst_p[2] |= pack_left_shift_u8(src_p->epsc_measured_current, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->epsc_measured_voltage, 0u, 0xffu);
+ epsc_measured_rpm = (uint16_t)src_p->epsc_measured_rpm;
+ dst_p[4] |= pack_right_shift_u16(epsc_measured_rpm, 4u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(epsc_measured_rpm, 4u, 0xf0u);
+ dst_p[5] |= pack_right_shift_u16(src_p->epsc_measured_temperature, 6u, 0x0fu);
+ dst_p[6] |= pack_left_shift_u16(src_p->epsc_measured_temperature, 2u, 0xfcu);
+ dst_p[6] |= pack_right_shift_u16(src_p->epsc_measured_internal_temp, 8u, 0x03u);
+ dst_p[7] |= pack_left_shift_u16(src_p->epsc_measured_internal_temp, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_epsc_out_unpack(
+ struct can1__main_ft24_epsc_out_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t epsc_measured_rpm;
+ uint16_t epsc_measured_steering_angle;
+
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ epsc_measured_steering_angle = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ epsc_measured_steering_angle |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->epsc_measured_steering_angle = (int16_t)epsc_measured_steering_angle;
+ dst_p->epsc_measured_current = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->epsc_measured_voltage = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ epsc_measured_rpm = unpack_left_shift_u16(src_p[4], 4u, 0xffu);
+ epsc_measured_rpm |= unpack_right_shift_u16(src_p[5], 4u, 0xf0u);
+
+ if ((epsc_measured_rpm & (1u << 11)) != 0u) {
+ epsc_measured_rpm |= 0xf000u;
+ }
+
+ dst_p->epsc_measured_rpm = (int16_t)epsc_measured_rpm;
+ dst_p->epsc_measured_temperature = unpack_left_shift_u16(src_p[5], 6u, 0x0fu);
+ dst_p->epsc_measured_temperature |= unpack_right_shift_u16(src_p[6], 2u, 0xfcu);
+ dst_p->epsc_measured_internal_temp = unpack_left_shift_u16(src_p[6], 8u, 0x03u);
+ dst_p->epsc_measured_internal_temp |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_epsc_out_init(struct can1__main_ft24_epsc_out_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_epsc_out_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_epsc_out_epsc_measured_steering_angle_encode(double value)
+{
+ return (int16_t)(value / 7.20721e-05);
+}
+
+double can1__main_ft24_epsc_out_epsc_measured_steering_angle_decode(int16_t value)
+{
+ return ((double)value * 7.20721e-05);
+}
+
+bool can1__main_ft24_epsc_out_epsc_measured_steering_angle_is_in_range(int16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_out_epsc_measured_current_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_out_epsc_measured_current_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_out_epsc_measured_current_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_out_epsc_measured_voltage_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_out_epsc_measured_voltage_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_out_epsc_measured_voltage_is_in_range(uint8_t value)
+{
+ return (value <= 200u);
+}
+
+int16_t can1__main_ft24_epsc_out_epsc_measured_rpm_encode(double value)
+{
+ return (int16_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_out_epsc_measured_rpm_decode(int16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_out_epsc_measured_rpm_is_in_range(int16_t value)
+{
+ return ((value >= -2048) && (value <= 2047));
+}
+
+uint16_t can1__main_ft24_epsc_out_epsc_measured_temperature_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_out_epsc_measured_temperature_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_out_epsc_measured_temperature_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+uint16_t can1__main_ft24_epsc_out_epsc_measured_internal_temp_encode(double value)
+{
+ return (uint16_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_out_epsc_measured_internal_temp_decode(uint16_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_out_epsc_measured_internal_temp_is_in_range(uint16_t value)
+{
+ return (value <= 1023u);
+}
+
+int can1__main_ft24_epsc_steering_in_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_epsc_steering_in_t *src_p,
+ size_t size)
+{
+ uint16_t epsc_desired_steering_angle;
+
+ if (size < 2u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 2);
+
+ epsc_desired_steering_angle = (uint16_t)src_p->epsc_desired_steering_angle;
+ dst_p[0] |= pack_right_shift_u16(epsc_desired_steering_angle, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(epsc_desired_steering_angle, 0u, 0xffu);
+
+ return (2);
+}
+
+int can1__main_ft24_epsc_steering_in_unpack(
+ struct can1__main_ft24_epsc_steering_in_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint16_t epsc_desired_steering_angle;
+
+ if (size < 2u) {
+ return (-EINVAL);
+ }
+
+ epsc_desired_steering_angle = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ epsc_desired_steering_angle |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->epsc_desired_steering_angle = (int16_t)epsc_desired_steering_angle;
+
+ return (0);
+}
+
+int can1__main_ft24_epsc_steering_in_init(struct can1__main_ft24_epsc_steering_in_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_epsc_steering_in_t));
+
+ return 0;
+}
+
+int16_t can1__main_ft24_epsc_steering_in_epsc_desired_steering_angle_encode(double value)
+{
+ return (int16_t)(value / 0.0001);
+}
+
+double can1__main_ft24_epsc_steering_in_epsc_desired_steering_angle_decode(int16_t value)
+{
+ return ((double)value * 0.0001);
+}
+
+bool can1__main_ft24_epsc_steering_in_epsc_desired_steering_angle_is_in_range(int16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_stw_buttons_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_buttons_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 1);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->stw_button_left, 0u, 0x01u);
+ dst_p[0] |= pack_left_shift_u8(src_p->stw_button_right, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->stw_button_r2_d, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->stw_button_enter, 3u, 0x08u);
+
+ return (1);
+}
+
+int can1__main_ft24_stw_buttons_unpack(
+ struct can1__main_ft24_stw_buttons_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 1u) {
+ return (-EINVAL);
+ }
+
+ dst_p->stw_button_left = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
+ dst_p->stw_button_right = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->stw_button_r2_d = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->stw_button_enter = unpack_right_shift_u8(src_p[0], 3u, 0x08u);
+
+ return (0);
+}
+
+int can1__main_ft24_stw_buttons_init(struct can1__main_ft24_stw_buttons_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_stw_buttons_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_stw_buttons_stw_button_left_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_buttons_stw_button_left_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_buttons_stw_button_left_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_buttons_stw_button_right_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_buttons_stw_button_right_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_buttons_stw_button_right_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_buttons_stw_button_r2_d_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_buttons_stw_button_r2_d_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_buttons_stw_button_r2_d_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_buttons_stw_button_enter_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_buttons_stw_button_enter_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_buttons_stw_button_enter_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+int can1__main_ft24_stw_status_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_stw_status_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 6);
+
+ dst_p[0] |= pack_left_shift_u8(src_p->as_state_stw, 0u, 0x07u);
+ dst_p[0] |= pack_left_shift_u8(src_p->r2_d_progress, 4u, 0xf0u);
+ dst_p[1] |= pack_left_shift_u8(src_p->inv_l_ready, 0u, 0x01u);
+ dst_p[1] |= pack_left_shift_u8(src_p->inv_r_ready, 1u, 0x02u);
+ dst_p[1] |= pack_left_shift_u8(src_p->sdc_bfl, 2u, 0x04u);
+ dst_p[1] |= pack_left_shift_u8(src_p->sdc_brl, 3u, 0x08u);
+ dst_p[1] |= pack_left_shift_u8(src_p->sdc_acc, 4u, 0x10u);
+ dst_p[1] |= pack_left_shift_u8(src_p->sdc_hvb, 5u, 0x20u);
+ dst_p[2] |= pack_left_shift_u8(src_p->lap_count, 0u, 0x3fu);
+ dst_p[3] |= pack_left_shift_u8(src_p->ini_chk_state, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_sdc, 0u, 0x01u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_ams, 1u, 0x02u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_pdu, 2u, 0x04u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_ini_chk, 3u, 0x08u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_con_mon, 4u, 0x10u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_scs, 5u, 0x20u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_s_bspd, 6u, 0x40u);
+ dst_p[4] |= pack_left_shift_u8(src_p->err_app_sp, 7u, 0x80u);
+ dst_p[5] |= pack_left_shift_u8(src_p->err_as, 0u, 0x01u);
+ dst_p[5] |= pack_left_shift_u8(src_p->err_ros, 1u, 0x02u);
+ dst_p[5] |= pack_left_shift_u8(src_p->err_res, 2u, 0x04u);
+ dst_p[5] |= pack_left_shift_u8(src_p->err_inv_l, 3u, 0x08u);
+ dst_p[5] |= pack_left_shift_u8(src_p->err_inv_r, 4u, 0x10u);
+
+ return (6);
+}
+
+int can1__main_ft24_stw_status_unpack(
+ struct can1__main_ft24_stw_status_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 6u) {
+ return (-EINVAL);
+ }
+
+ dst_p->as_state_stw = unpack_right_shift_u8(src_p[0], 0u, 0x07u);
+ dst_p->r2_d_progress = unpack_right_shift_u8(src_p[0], 4u, 0xf0u);
+ dst_p->inv_l_ready = unpack_right_shift_u8(src_p[1], 0u, 0x01u);
+ dst_p->inv_r_ready = unpack_right_shift_u8(src_p[1], 1u, 0x02u);
+ dst_p->sdc_bfl = unpack_right_shift_u8(src_p[1], 2u, 0x04u);
+ dst_p->sdc_brl = unpack_right_shift_u8(src_p[1], 3u, 0x08u);
+ dst_p->sdc_acc = unpack_right_shift_u8(src_p[1], 4u, 0x10u);
+ dst_p->sdc_hvb = unpack_right_shift_u8(src_p[1], 5u, 0x20u);
+ dst_p->lap_count = unpack_right_shift_u8(src_p[2], 0u, 0x3fu);
+ dst_p->ini_chk_state = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->err_sdc = unpack_right_shift_u8(src_p[4], 0u, 0x01u);
+ dst_p->err_ams = unpack_right_shift_u8(src_p[4], 1u, 0x02u);
+ dst_p->err_pdu = unpack_right_shift_u8(src_p[4], 2u, 0x04u);
+ dst_p->err_ini_chk = unpack_right_shift_u8(src_p[4], 3u, 0x08u);
+ dst_p->err_con_mon = unpack_right_shift_u8(src_p[4], 4u, 0x10u);
+ dst_p->err_scs = unpack_right_shift_u8(src_p[4], 5u, 0x20u);
+ dst_p->err_s_bspd = unpack_right_shift_u8(src_p[4], 6u, 0x40u);
+ dst_p->err_app_sp = unpack_right_shift_u8(src_p[4], 7u, 0x80u);
+ dst_p->err_as = unpack_right_shift_u8(src_p[5], 0u, 0x01u);
+ dst_p->err_ros = unpack_right_shift_u8(src_p[5], 1u, 0x02u);
+ dst_p->err_res = unpack_right_shift_u8(src_p[5], 2u, 0x04u);
+ dst_p->err_inv_l = unpack_right_shift_u8(src_p[5], 3u, 0x08u);
+ dst_p->err_inv_r = unpack_right_shift_u8(src_p[5], 4u, 0x10u);
+
+ return (0);
+}
+
+int can1__main_ft24_stw_status_init(struct can1__main_ft24_stw_status_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_stw_status_t));
+
+ return 0;
+}
+
+uint8_t can1__main_ft24_stw_status_as_state_stw_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_as_state_stw_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_as_state_stw_is_in_range(uint8_t value)
+{
+ return (value <= 5u);
+}
+
+uint8_t can1__main_ft24_stw_status_r2_d_progress_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_r2_d_progress_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_r2_d_progress_is_in_range(uint8_t value)
+{
+ return (value <= 15u);
+}
+
+uint8_t can1__main_ft24_stw_status_inv_l_ready_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_inv_l_ready_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_inv_l_ready_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_inv_r_ready_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_inv_r_ready_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_inv_r_ready_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_sdc_bfl_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_sdc_bfl_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_sdc_bfl_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_sdc_brl_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_sdc_brl_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_sdc_brl_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_sdc_acc_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_sdc_acc_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_sdc_acc_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_sdc_hvb_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_sdc_hvb_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_sdc_hvb_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_lap_count_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_lap_count_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_lap_count_is_in_range(uint8_t value)
+{
+ return (value <= 64u);
+}
+
+uint8_t can1__main_ft24_stw_status_ini_chk_state_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_ini_chk_state_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_ini_chk_state_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_stw_status_err_sdc_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_sdc_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_sdc_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_ams_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_ams_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_ams_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_pdu_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_pdu_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_pdu_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_ini_chk_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_ini_chk_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_ini_chk_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_con_mon_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_con_mon_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_con_mon_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_scs_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_scs_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_scs_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_s_bspd_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_s_bspd_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_s_bspd_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_app_sp_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_app_sp_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_app_sp_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_as_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_as_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_as_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_ros_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_ros_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_ros_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_res_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_res_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_res_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_inv_l_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_inv_l_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_inv_l_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_stw_status_err_inv_r_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_stw_status_err_inv_r_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_stw_status_err_inv_r_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+int can1__main_ft24_pdu_current_1_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_1_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->pdu_alwayson_curr, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->pdu_alwayson_curr, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->pdu_misc_curr, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->pdu_misc_curr, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->pdu_inverter_curr, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->pdu_inverter_curr, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->pdu_shutdown_circuit_curr, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->pdu_shutdown_circuit_curr, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_pdu_current_1_unpack(
+ struct can1__main_ft24_pdu_current_1_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdu_alwayson_curr = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->pdu_alwayson_curr |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->pdu_misc_curr = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->pdu_misc_curr |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->pdu_inverter_curr = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->pdu_inverter_curr |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->pdu_shutdown_circuit_curr = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->pdu_shutdown_circuit_curr |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_pdu_current_1_init(struct can1__main_ft24_pdu_current_1_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_pdu_current_1_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_pdu_current_1_pdu_alwayson_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_1_pdu_alwayson_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_1_pdu_alwayson_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_1_pdu_misc_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_1_pdu_misc_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_1_pdu_misc_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_1_pdu_inverter_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_1_pdu_inverter_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_1_pdu_inverter_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_1_pdu_shutdown_circuit_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_1_pdu_shutdown_circuit_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_1_pdu_shutdown_circuit_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_pdu_current_2_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_2_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->pdu_fans_curr, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->pdu_fans_curr, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->pdu_pump_curr, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->pdu_pump_curr, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->pdu_aggregat_curr, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->pdu_aggregat_curr, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->pdu_steering_curr, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->pdu_steering_curr, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_pdu_current_2_unpack(
+ struct can1__main_ft24_pdu_current_2_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdu_fans_curr = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->pdu_fans_curr |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->pdu_pump_curr = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->pdu_pump_curr |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->pdu_aggregat_curr = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->pdu_aggregat_curr |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->pdu_steering_curr = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->pdu_steering_curr |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_pdu_current_2_init(struct can1__main_ft24_pdu_current_2_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_pdu_current_2_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_pdu_current_2_pdu_fans_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_2_pdu_fans_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_2_pdu_fans_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_2_pdu_pump_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_2_pdu_pump_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_2_pdu_pump_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_2_pdu_aggregat_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_2_pdu_aggregat_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_2_pdu_aggregat_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_2_pdu_steering_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_2_pdu_steering_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_2_pdu_steering_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_pdu_current_3_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_3_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->pdu_ebs_valve_1_curr, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->pdu_ebs_valve_1_curr, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->pdu_ebs_valve_2_curr, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->pdu_ebs_valve_2_curr, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->pdu_mode_valve_1_curr, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->pdu_mode_valve_1_curr, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->pdu_mode_valve_2_curr, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->pdu_mode_valve_2_curr, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_pdu_current_3_unpack(
+ struct can1__main_ft24_pdu_current_3_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdu_ebs_valve_1_curr = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->pdu_ebs_valve_1_curr |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->pdu_ebs_valve_2_curr = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->pdu_ebs_valve_2_curr |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->pdu_mode_valve_1_curr = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->pdu_mode_valve_1_curr |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->pdu_mode_valve_2_curr = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->pdu_mode_valve_2_curr |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_pdu_current_3_init(struct can1__main_ft24_pdu_current_3_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_pdu_current_3_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_pdu_current_3_pdu_ebs_valve_1_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_3_pdu_ebs_valve_1_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_3_pdu_ebs_valve_1_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_3_pdu_ebs_valve_2_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_3_pdu_ebs_valve_2_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_3_pdu_ebs_valve_2_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_3_pdu_mode_valve_1_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_3_pdu_mode_valve_1_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_3_pdu_mode_valve_1_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_3_pdu_mode_valve_2_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_3_pdu_mode_valve_2_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_3_pdu_mode_valve_2_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_pdu_current_4_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_pdu_current_4_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 8);
+
+ dst_p[0] |= pack_right_shift_u16(src_p->pdu_sensorbox_curr, 8u, 0xffu);
+ dst_p[1] |= pack_left_shift_u16(src_p->pdu_sensorbox_curr, 0u, 0xffu);
+ dst_p[2] |= pack_right_shift_u16(src_p->pdu_service_brake_curr, 8u, 0xffu);
+ dst_p[3] |= pack_left_shift_u16(src_p->pdu_service_brake_curr, 0u, 0xffu);
+ dst_p[4] |= pack_right_shift_u16(src_p->pdu_servos_curr, 8u, 0xffu);
+ dst_p[5] |= pack_left_shift_u16(src_p->pdu_servos_curr, 0u, 0xffu);
+ dst_p[6] |= pack_right_shift_u16(src_p->pdu_shutdown_circuit_curr, 8u, 0xffu);
+ dst_p[7] |= pack_left_shift_u16(src_p->pdu_shutdown_circuit_curr, 0u, 0xffu);
+
+ return (8);
+}
+
+int can1__main_ft24_pdu_current_4_unpack(
+ struct can1__main_ft24_pdu_current_4_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ if (size < 8u) {
+ return (-EINVAL);
+ }
+
+ dst_p->pdu_sensorbox_curr = unpack_left_shift_u16(src_p[0], 8u, 0xffu);
+ dst_p->pdu_sensorbox_curr |= unpack_right_shift_u16(src_p[1], 0u, 0xffu);
+ dst_p->pdu_service_brake_curr = unpack_left_shift_u16(src_p[2], 8u, 0xffu);
+ dst_p->pdu_service_brake_curr |= unpack_right_shift_u16(src_p[3], 0u, 0xffu);
+ dst_p->pdu_servos_curr = unpack_left_shift_u16(src_p[4], 8u, 0xffu);
+ dst_p->pdu_servos_curr |= unpack_right_shift_u16(src_p[5], 0u, 0xffu);
+ dst_p->pdu_shutdown_circuit_curr = unpack_left_shift_u16(src_p[6], 8u, 0xffu);
+ dst_p->pdu_shutdown_circuit_curr |= unpack_right_shift_u16(src_p[7], 0u, 0xffu);
+
+ return (0);
+}
+
+int can1__main_ft24_pdu_current_4_init(struct can1__main_ft24_pdu_current_4_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_pdu_current_4_t));
+
+ return 0;
+}
+
+uint16_t can1__main_ft24_pdu_current_4_pdu_sensorbox_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_4_pdu_sensorbox_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_4_pdu_sensorbox_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_4_pdu_service_brake_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_4_pdu_service_brake_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_4_pdu_service_brake_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_4_pdu_servos_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_4_pdu_servos_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_4_pdu_servos_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint16_t can1__main_ft24_pdu_current_4_pdu_shutdown_circuit_curr_encode(double value)
+{
+ return (uint16_t)(value);
+}
+
+double can1__main_ft24_pdu_current_4_pdu_shutdown_circuit_curr_decode(uint16_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_pdu_current_4_pdu_shutdown_circuit_curr_is_in_range(uint16_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+int can1__main_ft24_epsc_config_in_pack(
+ uint8_t *dst_p,
+ const struct can1__main_ft24_epsc_config_in_t *src_p,
+ size_t size)
+{
+ uint8_t epsc_should_calibrate;
+
+ if (size < 7u) {
+ return (-EINVAL);
+ }
+
+ memset(&dst_p[0], 0, 7);
+
+ epsc_should_calibrate = (uint8_t)src_p->epsc_should_calibrate;
+ dst_p[0] |= pack_left_shift_u8(epsc_should_calibrate, 7u, 0x80u);
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_should_change_mode, 6u, 0x40u);
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_flag3, 4u, 0x10u);
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_flag4, 3u, 0x08u);
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_flag5, 2u, 0x04u);
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_flag6, 1u, 0x02u);
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_flag7, 0u, 0x01u);
+
+ switch (src_p->epsc_should_change_mode) {
+
+ case 1:
+ dst_p[0] |= pack_left_shift_u8(src_p->epsc_mode, 5u, 0x20u);
+ dst_p[1] |= pack_left_shift_u8(src_p->epsc_kp_pos, 0u, 0xffu);
+ dst_p[2] |= pack_left_shift_u8(src_p->epsc_ki_pos, 0u, 0xffu);
+ dst_p[3] |= pack_left_shift_u8(src_p->epsc_kp_rpm, 0u, 0xffu);
+ dst_p[4] |= pack_left_shift_u8(src_p->epsc_ki_rpm, 0u, 0xffu);
+ dst_p[5] |= pack_left_shift_u8(src_p->epsc_kp_curr, 0u, 0xffu);
+ dst_p[6] |= pack_left_shift_u8(src_p->epsc_ki_curr, 0u, 0xffu);
+ break;
+
+ default:
+ break;
+ }
+
+ return (7);
+}
+
+int can1__main_ft24_epsc_config_in_unpack(
+ struct can1__main_ft24_epsc_config_in_t *dst_p,
+ const uint8_t *src_p,
+ size_t size)
+{
+ uint8_t epsc_should_calibrate;
+
+ if (size < 7u) {
+ return (-EINVAL);
+ }
+
+ epsc_should_calibrate = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
+
+ if ((epsc_should_calibrate & (1u << 0)) != 0u) {
+ epsc_should_calibrate |= 0xfeu;
+ }
+
+ dst_p->epsc_should_calibrate = (int8_t)epsc_should_calibrate;
+ dst_p->epsc_should_change_mode = unpack_right_shift_u8(src_p[0], 6u, 0x40u);
+ dst_p->epsc_flag3 = unpack_right_shift_u8(src_p[0], 4u, 0x10u);
+ dst_p->epsc_flag4 = unpack_right_shift_u8(src_p[0], 3u, 0x08u);
+ dst_p->epsc_flag5 = unpack_right_shift_u8(src_p[0], 2u, 0x04u);
+ dst_p->epsc_flag6 = unpack_right_shift_u8(src_p[0], 1u, 0x02u);
+ dst_p->epsc_flag7 = unpack_right_shift_u8(src_p[0], 0u, 0x01u);
+
+ switch (dst_p->epsc_should_change_mode) {
+
+ case 1:
+ dst_p->epsc_mode = unpack_right_shift_u8(src_p[0], 5u, 0x20u);
+ dst_p->epsc_kp_pos = unpack_right_shift_u8(src_p[1], 0u, 0xffu);
+ dst_p->epsc_ki_pos = unpack_right_shift_u8(src_p[2], 0u, 0xffu);
+ dst_p->epsc_kp_rpm = unpack_right_shift_u8(src_p[3], 0u, 0xffu);
+ dst_p->epsc_ki_rpm = unpack_right_shift_u8(src_p[4], 0u, 0xffu);
+ dst_p->epsc_kp_curr = unpack_right_shift_u8(src_p[5], 0u, 0xffu);
+ dst_p->epsc_ki_curr = unpack_right_shift_u8(src_p[6], 0u, 0xffu);
+ break;
+
+ default:
+ break;
+ }
+
+ return (0);
+}
+
+int can1__main_ft24_epsc_config_in_init(struct can1__main_ft24_epsc_config_in_t *msg_p)
+{
+ if (msg_p == NULL) return -1;
+
+ memset(msg_p, 0, sizeof(struct can1__main_ft24_epsc_config_in_t));
+
+ return 0;
+}
+
+int8_t can1__main_ft24_epsc_config_in_epsc_should_calibrate_encode(double value)
+{
+ return (int8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_should_calibrate_decode(int8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_should_calibrate_is_in_range(int8_t value)
+{
+ return ((value >= 0) && (value <= 1));
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_should_change_mode_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_should_change_mode_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_should_change_mode_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_mode_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_mode_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_mode_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag3_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_flag3_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_flag3_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag4_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_flag4_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_flag4_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag5_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_flag5_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_flag5_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag6_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_flag6_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_flag6_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_flag7_encode(double value)
+{
+ return (uint8_t)(value);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_flag7_decode(uint8_t value)
+{
+ return ((double)value);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_flag7_is_in_range(uint8_t value)
+{
+ return (value <= 1u);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_kp_pos_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_kp_pos_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_kp_pos_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_ki_pos_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_ki_pos_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_ki_pos_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_kp_rpm_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_kp_rpm_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_kp_rpm_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_ki_rpm_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_ki_rpm_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_ki_rpm_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_kp_curr_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_kp_curr_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_kp_curr_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
+
+uint8_t can1__main_ft24_epsc_config_in_epsc_ki_curr_encode(double value)
+{
+ return (uint8_t)(value / 0.1);
+}
+
+double can1__main_ft24_epsc_config_in_epsc_ki_curr_decode(uint8_t value)
+{
+ return ((double)value * 0.1);
+}
+
+bool can1__main_ft24_epsc_config_in_epsc_ki_curr_is_in_range(uint8_t value)
+{
+ (void)value;
+
+ return (true);
+}
diff --git a/src/ros2_control_can/src/fake_robot.cpp b/src/ros2_control_can/src/fake_robot.cpp
deleted file mode 100644
index 3eeb863..0000000
--- a/src/ros2_control_can/src/fake_robot.cpp
+++ /dev/null
@@ -1,129 +0,0 @@
-#include "ros2_control_can/fake_robot.h"
-
-
-#include "hardware_interface/types/hardware_interface_type_values.hpp"
-
-#include "rclcpp/rclcpp.hpp"
-#include
-
-
-CallbackReturn FakeRobot::on_init(const hardware_interface::HardwareInfo & info)
-{
- if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS)
-{
- return CallbackReturn::ERROR;
-}
-
- RCLCPP_INFO(logger_, "Configuring Fakerobot...");
-
- time_ = std::chrono::system_clock::now();
-
- cfg_.left_wheel_name = info_.hardware_parameters["left_wheel_name"];
- cfg_.right_wheel_name = info_.hardware_parameters["right_wheel_name"];
-
-
- // Set up the wheels
- // Note: It doesn't matter that we haven't set encoder counts per rev
- // since the fake robot bypasses the encoder code completely
-
- l_wheel_.setup(cfg_.left_wheel_name);
- r_wheel_.setup(cfg_.right_wheel_name);
-
- RCLCPP_INFO(logger_, "Finished Configuration Fakerobot");
-
- return CallbackReturn::SUCCESS;
-}
-
-std::vector FakeRobot::export_state_interfaces()
-{
- // We need to set up a position and a velocity interface for each wheel
-
- std::vector state_interfaces;
-
- state_interfaces.emplace_back(hardware_interface::StateInterface(l_wheel_.name, hardware_interface::HW_IF_VELOCITY, &l_wheel_.vel));
- state_interfaces.emplace_back(hardware_interface::StateInterface(l_wheel_.name, hardware_interface::HW_IF_POSITION, &l_wheel_.pos));
- state_interfaces.emplace_back(hardware_interface::StateInterface(r_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_wheel_.vel));
- state_interfaces.emplace_back(hardware_interface::StateInterface(r_wheel_.name, hardware_interface::HW_IF_POSITION, &r_wheel_.pos));
-
- return state_interfaces;
-}
-
-std::vector FakeRobot::export_command_interfaces()
-{
- // We need to set up a velocity command interface for each wheel
-
- std::vector command_interfaces;
-
- command_interfaces.emplace_back(hardware_interface::CommandInterface(l_wheel_.name, hardware_interface::HW_IF_VELOCITY, &l_wheel_.cmd));
- command_interfaces.emplace_back(hardware_interface::CommandInterface(r_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_wheel_.cmd));
-
- return command_interfaces;
-}
-
-
-
-#if OLD_ROS_CONTROL_SIGNATURE
-return_type FakeRobot::read()
-#else
-return_type FakeRobot::read(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */)
-#endif
-{
-
- // TODO fix chrono duration
-
- // Calculate time delta
- auto new_time = std::chrono::system_clock::now();
- std::chrono::duration diff = new_time - time_;
- double deltaSeconds = diff.count();
- time_ = new_time;
-
-
- // Force the wheel position
- l_wheel_.pos = l_wheel_.pos + l_wheel_.vel * deltaSeconds;
- r_wheel_.pos = r_wheel_.pos + r_wheel_.vel * deltaSeconds;
-
- return return_type::OK;
-
-
-}
-
-#if OLD_ROS_CONTROL_SIGNATURE
-return_type FakeRobot::write()
-#else
-return_type FakeRobot::write(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */)
-#endif
-{
-
- // Set the wheel velocities to directly match what is commanded
-
- l_wheel_.vel = l_wheel_.cmd;
- r_wheel_.vel = r_wheel_.cmd;
-
-
- return return_type::OK;
-}
-
-#if OLD_ROS_CONTROL_SIGNATURE
-CallbackReturn FakeRobot::on_activate(const rclcpp_lifecycle::State & /* previous_state */, const rclcpp_lifecycle::State & /* current_state */)
-#else
-CallbackReturn FakeRobot::on_activate(const rclcpp_lifecycle::State & /* previous_state */)
-#endif
-{
- RCLCPP_INFO(logger_, "Starting Controller...");
-
- return CallbackReturn::SUCCESS;
-}
-
-CallbackReturn FakeRobot::on_deactivate(const rclcpp_lifecycle::State & /* previous_state */)
-{
- RCLCPP_INFO(logger_, "Stopping Controller...");
-
- return CallbackReturn::SUCCESS;
-}
-
-#include "pluginlib/class_list_macros.hpp"
-
-PLUGINLIB_EXPORT_CLASS(
- FakeRobot,
- hardware_interface::SystemInterface
-)
\ No newline at end of file
diff --git a/src/ros2_control_can/src/ros2_control_can.cpp b/src/ros2_control_can/src/ros2_control_can.cpp
index f403d77..405452e 100644
--- a/src/ros2_control_can/src/ros2_control_can.cpp
+++ b/src/ros2_control_can/src/ros2_control_can.cpp
@@ -7,6 +7,13 @@
#include "rclcpp/rclcpp.hpp"
#include
+#include
+#include
+#include
+
+#include
+#include
+
#define RADSTORPM(a)(a*60.0/(2.0*M_PI))
#define RPMSTORADS(a)(a*2.0*M_PI/60.0)
#define REVSTORAD(a)(a*2.0*M_PI)
@@ -23,27 +30,29 @@ Ros2ControlCAN::Ros2ControlCAN()
CallbackReturn Ros2ControlCAN::on_init(const hardware_interface::HardwareInfo & info)
{
if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS)
-{
- return CallbackReturn::ERROR;
-}
+ {
+ return CallbackReturn::ERROR;
+ }
RCLCPP_INFO(logger_, "Configuring...");
time_ = std::chrono::system_clock::now();
- cfg_.left_wheel_name = info_.hardware_parameters["left_wheel_name"];
- cfg_.right_wheel_name = info_.hardware_parameters["right_wheel_name"];
+ cfg_.front_left_wheel_name = info_.hardware_parameters["front_left_wheel_name"];
+ cfg_.front_right_wheel_name = info_.hardware_parameters["front_right_wheel_name"];
+ cfg_.rear_left_wheel_name = info_.hardware_parameters["rear_left_wheel_name"];
+ cfg_.rear_right_wheel_name = info_.hardware_parameters["rear_right_wheel_name"];
cfg_.loop_rate = std::stof(info_.hardware_parameters["loop_rate"]);
cfg_.device = info_.hardware_parameters["device"];
- cfg_.baud_rate = std::stoi(info_.hardware_parameters["baud_rate"]);
- cfg_.timeout = std::stoi(info_.hardware_parameters["timeout"]);
// Set up the wheels
- l_wheel_.setup(cfg_.left_wheel_name);
- r_wheel_.setup(cfg_.right_wheel_name);
+ f_l_wheel_.setup(cfg_.front_left_wheel_name);
+ f_r_wheel_.setup(cfg_.front_right_wheel_name);
+ r_l_wheel_.setup(cfg_.front_left_wheel_name);
+ r_r_wheel_.setup(cfg_.front_right_wheel_name);
- // Set up the Arduino
- //arduino_.setup(cfg_.device, cfg_.baud_rate, cfg_.timeout);
+ // init tx frame
+ can1__main_ft24_jetson_tx_init(&tx_frame);
RCLCPP_INFO(logger_, "Finished Configuration");
@@ -56,10 +65,12 @@ std::vector Ros2ControlCAN::export_state_int
std::vector state_interfaces;
- state_interfaces.emplace_back(hardware_interface::StateInterface(l_wheel_.name, hardware_interface::HW_IF_VELOCITY, &l_wheel_.vel));
- state_interfaces.emplace_back(hardware_interface::StateInterface(l_wheel_.name, hardware_interface::HW_IF_POSITION, &l_wheel_.pos));
- state_interfaces.emplace_back(hardware_interface::StateInterface(r_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_wheel_.vel));
- state_interfaces.emplace_back(hardware_interface::StateInterface(r_wheel_.name, hardware_interface::HW_IF_POSITION, &r_wheel_.pos));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(f_l_wheel_.name, hardware_interface::HW_IF_POSITION, &f_l_wheel_.steer));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(f_r_wheel_.name, hardware_interface::HW_IF_POSITION, &f_r_wheel_.steer));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(r_l_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_l_wheel_.vel));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(r_r_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_r_wheel_.vel));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(r_l_wheel_.name, hardware_interface::HW_IF_POSITION, &r_l_wheel_.pos));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(r_r_wheel_.name, hardware_interface::HW_IF_POSITION, &r_r_wheel_.pos));
return state_interfaces;
}
@@ -70,8 +81,10 @@ std::vector Ros2ControlCAN::export_command
std::vector command_interfaces;
- command_interfaces.emplace_back(hardware_interface::CommandInterface(l_wheel_.name, hardware_interface::HW_IF_VELOCITY, &l_wheel_.cmd));
- command_interfaces.emplace_back(hardware_interface::CommandInterface(r_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_wheel_.cmd));
+ command_interfaces.emplace_back(hardware_interface::CommandInterface(f_l_wheel_.name, hardware_interface::HW_IF_POSITION, &f_l_wheel_.steer));
+ command_interfaces.emplace_back(hardware_interface::CommandInterface(f_r_wheel_.name, hardware_interface::HW_IF_POSITION, &f_r_wheel_.steer));
+ command_interfaces.emplace_back(hardware_interface::CommandInterface(r_l_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_l_wheel_.vel));
+ command_interfaces.emplace_back(hardware_interface::CommandInterface(r_r_wheel_.name, hardware_interface::HW_IF_VELOCITY, &r_r_wheel_.vel));
return command_interfaces;
}
@@ -80,13 +93,44 @@ CallbackReturn Ros2ControlCAN::on_activate(const rclcpp_lifecycle::State & previ
{
RCLCPP_INFO(logger_, "Starting Controller...");
- return CallbackReturn::SUCCESS;
-}
+ if ((socket_instance = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) {
+ perror("Socket");
+ return CallbackReturn::ERROR;
+ }
+
+ struct ifreq ifr;
+ const char *cstr = cfg_.device.c_str();
+ strcpy(ifr.ifr_name, cstr );
+ ioctl(socket_instance, SIOCGIFINDEX, &ifr);
+
+ struct sockaddr_can addr;
+ memset(&addr, 0, sizeof(addr));
+ addr.can_family = AF_CAN;
+ addr.can_ifindex = ifr.ifr_ifindex;
+ if (bind(socket_instance, (struct sockaddr *)&addr, sizeof(addr)) < 0) {
+ perror("Bind");
+ return CallbackReturn::ERROR;
+ }
+
+ struct can_filter rfilter[1];
+ rfilter[0].can_id = 0x550;
+ rfilter[0].can_mask = 0xFF0;
+ //rfilter[1].can_id = 0x200;
+ //rfilter[1].can_mask = 0x700;
+ setsockopt(socket_instance, SOL_CAN_RAW, CAN_RAW_FILTER, &rfilter, sizeof(rfilter));
+
+ return CallbackReturn::SUCCESS;
+ }
CallbackReturn Ros2ControlCAN::on_deactivate(const rclcpp_lifecycle::State & previous_state)
{
RCLCPP_INFO(logger_, "Stopping Controller...");
+ if (close(socket_instance) < 0) {
+ perror("Close");
+ return CallbackReturn::ERROR;
+ }
+
return CallbackReturn::SUCCESS;
}
@@ -101,20 +145,17 @@ return_type Ros2ControlCAN::read(const rclcpp::Time & /* time */, const rclcpp::
double deltaSeconds = diff.count();
time_ = new_time;
+
if (false)
{
return return_type::ERROR;
}
- //arduino_.readEncoderValues(l_wheel_.vel, r_wheel_.vel, l_wheel_.pos, r_wheel_.pos);
// convert rpm to rad/s
- l_wheel_.vel = RPMSTORADS(l_wheel_.vel);
- r_wheel_.vel = RPMSTORADS(r_wheel_.vel);
+ //l_wheel_.vel = RPMSTORADS(l_wheel_.vel);
+ //r_wheel_.vel = RPMSTORADS(r_wheel_.vel);
+
-
- // convert rev to rad
- l_wheel_.pos = REVSTORAD(l_wheel_.pos);
- r_wheel_.pos = REVSTORAD(r_wheel_.pos);
return return_type::OK;
}
@@ -124,8 +165,27 @@ return_type Ros2ControlCAN::write(const rclcpp::Time & /* time */, const rclcpp:
{
return return_type::ERROR;
}
- // convert rad/s to rpm and write to motors
- //arduino_.setMotorValues(RADSTORPM(l_wheel_.cmd), RADSTORPM(r_wheel_.cmd));
+
+ // send can frame
+ tx_frame.jetson_steering_angle = can1__main_ft24_jetson_tx_jetson_steering_angle_encode((f_l_wheel_.steer + f_r_wheel_.steer)/2.0);
+
+ // pack tx_frame
+ int tx_size = can1__main_ft24_jetson_tx_pack(can_buffer, &tx_frame, 64);
+
+ if (tx_size < 0) {
+ perror("Pack");
+ return return_type::ERROR;
+ }
+
+ // send tx_frame
+ struct can_frame frame;
+ frame.can_id = 0x550;
+ frame.can_dlc = tx_size;
+ memcpy(frame.data, can_buffer, tx_size);
+ if (::write(socket_instance, &frame, sizeof(struct can_frame)) < 0) {
+ perror("Write");
+ return return_type::ERROR;
+ }
return return_type::OK;
}
diff --git a/start.bash b/start.bash
deleted file mode 100755
index 0938e0d..0000000
--- a/start.bash
+++ /dev/null
@@ -1,59 +0,0 @@
-#!/bin/bash
-
-DCAITI_PATH=.
-
-# Define your windows, working dirs, and commands
-declare -a windows=(
- "performance"
- "robot_control"
- "remote_control"
- "lidar"
-# "slam"
- "nav2"
-)
-declare -a work_dirs=(
- $HOME
- $DCAITI_PATH
- $DCAITI_PATH/src/dcaitirobot/launch
- $DCAITI_PATH
- # $DCAITI_PATH/src/dcaitirobot/launch
- $DCAITI_PATH/src/dcaiti_navigation/launch
-)
-declare -a commands=(
- "htop"
- "ros2 launch ft24_control launch_robot.py"
- "ros2 launch remote_control_launch.py"
- "ros2 launch velodyne velodyne-all-nodes-VLP16-launch.py"
- # "ros2 launch launch_slam.py"
- "ros2 launch start_nav2.py"
-)
-
-# Start tmux
-tmux start-server
-
-SESSION=dcaiti
-
-# Create a new session without attaching yet
-tmux new-session -d -s $SESSION
-
-# Iterate over sessions array and create them
-for index in ${!windows[*]}; do
- window=${windows[$index]}
- work_dir=${work_dirs[$index]}
- command=${commands[$index]}
-
- # If it's the first window, rename the existing window, otherwise create a new one
- if [ $index -eq 0 ]; then
- tmux rename-window -t $SESSION:0 $window
- else
- tmux new-window -t $SESSION -n $window
- fi
-
- # Switch to work_dir and execute the command
- tmux send-keys -t $SESSION:$window "cd $work_dir" C-m
- tmux send-keys -t $SESSION:$window "$command" C-m
-done
-
-# Finally attach to the tmux session
-tmux attach-session -t $SESSION
-