├── .github
├── dependabot.yml
└── workflows
│ ├── arduino-lint.yml
│ ├── compile-examples.yml
│ ├── extra-library-checks.yml
│ ├── general-formatting-checks.yml
│ ├── report-size-deltas.yml
│ ├── smoke-test.yml
│ ├── spell-check.yml
│ ├── sync-labels.yml
│ └── unit-tests.yml
├── .gitignore
├── CMakeLists.txt
├── LICENSE
├── README.md
├── examples
└── CAN
│ ├── OpenCyphal-Blink
│ └── OpenCyphal-Blink.ino
│ ├── OpenCyphal-Heartbeat-Publisher
│ └── OpenCyphal-Heartbeat-Publisher.ino
│ ├── OpenCyphal-Heartbeat-Subscriber-With-Metadata
│ └── OpenCyphal-Heartbeat-Subscriber-With-Metadata.ino
│ ├── OpenCyphal-Heartbeat-Subscriber
│ └── OpenCyphal-Heartbeat-Subscriber.ino
│ ├── OpenCyphal-Service-Client-With-Metadata
│ └── OpenCyphal-Service-Client-With-Metadata.ino
│ ├── OpenCyphal-Service-Client
│ └── OpenCyphal-Service-Client.ino
│ ├── OpenCyphal-Service-Server
│ └── OpenCyphal-Service-Server.ino
│ └── host-example-01-opencyphal-basic-node
│ ├── .gitignore
│ ├── CMakeLists.txt
│ ├── README.md
│ ├── host-example-01-opencyphal-basic-node.cpp
│ ├── kv_host.cpp
│ ├── kv_host.h
│ ├── setup_vcan.sh
│ ├── setup_yakut.sh
│ ├── socketcan.c
│ └── socketcan.h
├── extras
├── codespell-ignore-words-list.txt
├── script
│ ├── Dockerfile
│ ├── README.md
│ ├── build_docker.sh
│ ├── docker_codegen.sh
│ └── update_cpp_header.sh
└── test
│ ├── CMakeLists.txt
│ ├── external
│ └── catch2
│ │ └── v2.13.10
│ │ └── include
│ │ └── catch2
│ │ └── catch.hpp
│ └── src
│ ├── test_main.cpp
│ ├── test_registry_impl.cpp
│ └── test_registry_value.cpp
├── keywords.txt
├── library.properties
└── src
├── 107-Arduino-Cyphal.h
├── CanRxQueueItem.hpp
├── CircularBuffer.hpp
├── CircularBuffer.ipp
├── DSDL_Types.h
├── DSDL_Types.h.impl
├── Node.cpp
├── Node.hpp
├── Node.ipp
├── Publisher.hpp
├── Publisher.ipp
├── PublisherBase.hpp
├── ServiceClient.hpp
├── ServiceClient.ipp
├── ServiceClientBase.hpp
├── ServiceServer.hpp
├── ServiceServer.ipp
├── ServiceServerBase.hpp
├── Subscription.hpp
├── Subscription.ipp
├── SubscriptionBase.h
├── cyphal++
└── cyphal++.h
├── libcanard
├── .clang-tidy
├── _canard_cavl.h
├── canard.c
└── canard.h
├── libo1heap
├── .clang-tidy
├── o1heap.c
└── o1heap.h
├── nunavut
└── support
│ ├── serialization.hpp
│ └── variable_length_array.hpp
├── types
├── reg
│ └── udral
│ │ ├── physics
│ │ ├── acoustics
│ │ │ └── Note_0_1.hpp
│ │ ├── dynamics
│ │ │ ├── rotation
│ │ │ │ ├── PlanarTs_0_1.hpp
│ │ │ │ └── Planar_0_1.hpp
│ │ │ └── translation
│ │ │ │ ├── LinearTs_0_1.hpp
│ │ │ │ └── Linear_0_1.hpp
│ │ ├── electricity
│ │ │ ├── PowerTs_0_1.hpp
│ │ │ ├── Power_0_1.hpp
│ │ │ ├── SourceTs_0_1.hpp
│ │ │ └── Source_0_1.hpp
│ │ ├── kinematics
│ │ │ ├── cartesian
│ │ │ │ ├── PointStateVarTs_0_1.hpp
│ │ │ │ ├── PointStateVar_0_1.hpp
│ │ │ │ ├── PointState_0_1.hpp
│ │ │ │ ├── PointVar_0_1.hpp
│ │ │ │ ├── Point_0_1.hpp
│ │ │ │ ├── PoseVarTs_0_1.hpp
│ │ │ │ ├── PoseVar_0_1.hpp
│ │ │ │ ├── Pose_0_1.hpp
│ │ │ │ ├── StateVarTs_0_1.hpp
│ │ │ │ ├── StateVar_0_1.hpp
│ │ │ │ ├── State_0_1.hpp
│ │ │ │ ├── TwistVarTs_0_1.hpp
│ │ │ │ ├── TwistVar_0_1.hpp
│ │ │ │ └── Twist_0_1.hpp
│ │ │ ├── geodetic
│ │ │ │ ├── PointStateVarTs_0_1.hpp
│ │ │ │ ├── PointStateVar_0_1.hpp
│ │ │ │ ├── PointState_0_1.hpp
│ │ │ │ ├── PointVar_0_1.hpp
│ │ │ │ ├── Point_0_1.hpp
│ │ │ │ ├── PoseVar_0_1.hpp
│ │ │ │ ├── Pose_0_1.hpp
│ │ │ │ ├── StateVarTs_0_1.hpp
│ │ │ │ ├── StateVar_0_1.hpp
│ │ │ │ └── State_0_1.hpp
│ │ │ ├── rotation
│ │ │ │ ├── PlanarTs_0_1.hpp
│ │ │ │ └── Planar_0_1.hpp
│ │ │ └── translation
│ │ │ │ ├── LinearTs_0_1.hpp
│ │ │ │ ├── LinearVarTs_0_1.hpp
│ │ │ │ ├── Linear_0_1.hpp
│ │ │ │ ├── Velocity1VarTs_0_1.hpp
│ │ │ │ ├── Velocity3Var_0_1.hpp
│ │ │ │ └── Velocity3Var_0_2.hpp
│ │ ├── optics
│ │ │ └── HighColor_0_1.hpp
│ │ ├── thermodynamics
│ │ │ └── PressureTempVarTs_0_1.hpp
│ │ └── time
│ │ │ ├── TAI64VarTs_0_1.hpp
│ │ │ ├── TAI64Var_0_1.hpp
│ │ │ └── TAI64_0_1.hpp
│ │ └── service
│ │ ├── actuator
│ │ ├── common
│ │ │ ├── FaultFlags_0_1.hpp
│ │ │ ├── Feedback_0_1.hpp
│ │ │ ├── Status_0_1.hpp
│ │ │ ├── sp
│ │ │ │ ├── Scalar_0_1.hpp
│ │ │ │ ├── Vector2_0_1.hpp
│ │ │ │ ├── Vector31_0_1.hpp
│ │ │ │ ├── Vector3_0_1.hpp
│ │ │ │ ├── Vector4_0_1.hpp
│ │ │ │ ├── Vector6_0_1.hpp
│ │ │ │ ├── Vector8_0_1.hpp
│ │ │ │ └── zX005FzX005F0_1.hpp
│ │ │ └── zX005FzX005F0_1.hpp
│ │ ├── esc
│ │ │ └── zX005FzX005F0_1.hpp
│ │ └── servo
│ │ │ └── zX005FzX005F0_1.hpp
│ │ ├── battery
│ │ ├── Error_0_1.hpp
│ │ ├── Parameters_0_3.hpp
│ │ ├── Status_0_2.hpp
│ │ ├── Technology_0_1.hpp
│ │ └── zX005FzX005F0_1.hpp
│ │ ├── common
│ │ ├── Heartbeat_0_1.hpp
│ │ └── Readiness_0_1.hpp
│ │ └── sensor
│ │ └── Status_0_1.hpp
├── uavcan
│ ├── _register
│ │ ├── Access_1_0.hpp
│ │ ├── List_1_0.hpp
│ │ ├── Name_1_0.hpp
│ │ └── Value_1_0.hpp
│ ├── diagnostic
│ │ ├── Record_1_0.hpp
│ │ ├── Record_1_1.hpp
│ │ └── Severity_1_0.hpp
│ ├── file
│ │ ├── Error_1_0.hpp
│ │ ├── GetInfo_0_1.hpp
│ │ ├── GetInfo_0_2.hpp
│ │ ├── List_0_1.hpp
│ │ ├── List_0_2.hpp
│ │ ├── Modify_1_0.hpp
│ │ ├── Modify_1_1.hpp
│ │ ├── Path_1_0.hpp
│ │ ├── Path_2_0.hpp
│ │ ├── Read_1_0.hpp
│ │ ├── Read_1_1.hpp
│ │ ├── Write_1_0.hpp
│ │ └── Write_1_1.hpp
│ ├── internet
│ │ └── udp
│ │ │ ├── HandleIncomingPacket_0_1.hpp
│ │ │ ├── HandleIncomingPacket_0_2.hpp
│ │ │ ├── OutgoingPacket_0_1.hpp
│ │ │ └── OutgoingPacket_0_2.hpp
│ ├── metatransport
│ │ ├── can
│ │ │ ├── ArbitrationID_0_1.hpp
│ │ │ ├── BaseArbitrationID_0_1.hpp
│ │ │ ├── DataClassic_0_1.hpp
│ │ │ ├── DataFD_0_1.hpp
│ │ │ ├── Error_0_1.hpp
│ │ │ ├── ExtendedArbitrationID_0_1.hpp
│ │ │ ├── Frame_0_1.hpp
│ │ │ ├── Frame_0_2.hpp
│ │ │ ├── Manifestation_0_1.hpp
│ │ │ └── RTR_0_1.hpp
│ │ ├── ethernet
│ │ │ ├── EtherType_0_1.hpp
│ │ │ └── Frame_0_1.hpp
│ │ ├── serial
│ │ │ ├── Fragment_0_1.hpp
│ │ │ └── Fragment_0_2.hpp
│ │ └── udp
│ │ │ ├── Endpoint_0_1.hpp
│ │ │ └── Frame_0_1.hpp
│ ├── node
│ │ ├── ExecuteCommand_1_0.hpp
│ │ ├── ExecuteCommand_1_1.hpp
│ │ ├── ExecuteCommand_1_2.hpp
│ │ ├── ExecuteCommand_1_3.hpp
│ │ ├── GetInfo_1_0.hpp
│ │ ├── GetTransportStatistics_0_1.hpp
│ │ ├── Health_1_0.hpp
│ │ ├── Heartbeat_1_0.hpp
│ │ ├── ID_1_0.hpp
│ │ ├── IOStatistics_0_1.hpp
│ │ ├── Mode_1_0.hpp
│ │ ├── Version_1_0.hpp
│ │ └── port
│ │ │ ├── ID_1_0.hpp
│ │ │ ├── List_0_1.hpp
│ │ │ ├── List_1_0.hpp
│ │ │ ├── ServiceIDList_0_1.hpp
│ │ │ ├── ServiceIDList_1_0.hpp
│ │ │ ├── ServiceID_1_0.hpp
│ │ │ ├── SubjectIDList_0_1.hpp
│ │ │ ├── SubjectIDList_1_0.hpp
│ │ │ └── SubjectID_1_0.hpp
│ ├── pnp
│ │ ├── NodeIDAllocationData_1_0.hpp
│ │ ├── NodeIDAllocationData_2_0.hpp
│ │ └── cluster
│ │ │ ├── AppendEntries_1_0.hpp
│ │ │ ├── Discovery_1_0.hpp
│ │ │ ├── Entry_1_0.hpp
│ │ │ └── RequestVote_1_0.hpp
│ ├── primitive
│ │ ├── Empty_1_0.hpp
│ │ ├── String_1_0.hpp
│ │ ├── Unstructured_1_0.hpp
│ │ ├── array
│ │ │ ├── Bit_1_0.hpp
│ │ │ ├── Integer16_1_0.hpp
│ │ │ ├── Integer32_1_0.hpp
│ │ │ ├── Integer64_1_0.hpp
│ │ │ ├── Integer8_1_0.hpp
│ │ │ ├── Natural16_1_0.hpp
│ │ │ ├── Natural32_1_0.hpp
│ │ │ ├── Natural64_1_0.hpp
│ │ │ ├── Natural8_1_0.hpp
│ │ │ ├── Real16_1_0.hpp
│ │ │ ├── Real32_1_0.hpp
│ │ │ └── Real64_1_0.hpp
│ │ └── scalar
│ │ │ ├── Bit_1_0.hpp
│ │ │ ├── Integer16_1_0.hpp
│ │ │ ├── Integer32_1_0.hpp
│ │ │ ├── Integer64_1_0.hpp
│ │ │ ├── Integer8_1_0.hpp
│ │ │ ├── Natural16_1_0.hpp
│ │ │ ├── Natural32_1_0.hpp
│ │ │ ├── Natural64_1_0.hpp
│ │ │ ├── Natural8_1_0.hpp
│ │ │ ├── Real16_1_0.hpp
│ │ │ ├── Real32_1_0.hpp
│ │ │ └── Real64_1_0.hpp
│ ├── si
│ │ ├── sample
│ │ │ ├── acceleration
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── angle
│ │ │ │ ├── Quaternion_1_0.hpp
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── angular_acceleration
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── angular_velocity
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── duration
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── WideScalar_1_0.hpp
│ │ │ ├── electric_charge
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── electric_current
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── energy
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── force
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── frequency
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── length
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ ├── Vector3_1_0.hpp
│ │ │ │ ├── WideScalar_1_0.hpp
│ │ │ │ └── WideVector3_1_0.hpp
│ │ │ ├── luminance
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── magnetic_field_strength
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ ├── Scalar_1_1.hpp
│ │ │ │ ├── Vector3_1_0.hpp
│ │ │ │ └── Vector3_1_1.hpp
│ │ │ ├── magnetic_flux_density
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── mass
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── power
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── pressure
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── temperature
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── torque
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── velocity
│ │ │ │ ├── Scalar_1_0.hpp
│ │ │ │ └── Vector3_1_0.hpp
│ │ │ ├── voltage
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ ├── volume
│ │ │ │ └── Scalar_1_0.hpp
│ │ │ └── volumetric_flow_rate
│ │ │ │ └── Scalar_1_0.hpp
│ │ └── unit
│ │ │ ├── acceleration
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── angle
│ │ │ ├── Quaternion_1_0.hpp
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── angular_acceleration
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── angular_velocity
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── duration
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── WideScalar_1_0.hpp
│ │ │ ├── electric_charge
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── electric_current
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── energy
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── force
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── frequency
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── length
│ │ │ ├── Scalar_1_0.hpp
│ │ │ ├── Vector3_1_0.hpp
│ │ │ ├── WideScalar_1_0.hpp
│ │ │ └── WideVector3_1_0.hpp
│ │ │ ├── luminance
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── magnetic_field_strength
│ │ │ ├── Scalar_1_0.hpp
│ │ │ ├── Scalar_1_1.hpp
│ │ │ ├── Vector3_1_0.hpp
│ │ │ └── Vector3_1_1.hpp
│ │ │ ├── magnetic_flux_density
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── mass
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── power
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── pressure
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── temperature
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── torque
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── velocity
│ │ │ ├── Scalar_1_0.hpp
│ │ │ └── Vector3_1_0.hpp
│ │ │ ├── voltage
│ │ │ └── Scalar_1_0.hpp
│ │ │ ├── volume
│ │ │ └── Scalar_1_0.hpp
│ │ │ └── volumetric_flow_rate
│ │ │ └── Scalar_1_0.hpp
│ └── time
│ │ ├── GetSynchronizationMasterInfo_0_1.hpp
│ │ ├── Synchronization_1_0.hpp
│ │ ├── SynchronizedTimestamp_1_0.hpp
│ │ ├── TAIInfo_0_1.hpp
│ │ └── TimeSystem_0_1.hpp
└── zubax
│ ├── bridge
│ └── can
│ │ ├── BaseFilterConfig_1_0.hpp
│ │ ├── BusErrorCounters_1_0.hpp
│ │ ├── ConfigResult_1_0.hpp
│ │ ├── Configuration_1_0.hpp
│ │ ├── ExtendedFilterConfig_1_0.hpp
│ │ ├── FaultConfinementStatus_1_0.hpp
│ │ ├── FilterConfig_1_0.hpp
│ │ ├── FrameCounters_1_0.hpp
│ │ ├── FrameTs_0_1.hpp
│ │ ├── PhysicalConfig_1_0.hpp
│ │ ├── Status_1_0.hpp
│ │ └── TimingConfig_1_0.hpp
│ ├── fluxgrip
│ └── Feedback_0_1.hpp
│ ├── low_level_io
│ ├── Access_0_1.hpp
│ ├── Access_1_0.hpp
│ ├── Data_0_1.hpp
│ └── Data_1_0.hpp
│ ├── physics
│ ├── dynamics
│ │ ├── DoF2ndTs_0_1.hpp
│ │ ├── DoF2ndTs_1_0.hpp
│ │ ├── DoF2nd_0_1.hpp
│ │ ├── DoF2nd_1_0.hpp
│ │ ├── DoF3rdTs_0_1.hpp
│ │ ├── DoF3rdTs_1_0.hpp
│ │ ├── DoF3rd_0_1.hpp
│ │ └── DoF3rd_1_0.hpp
│ ├── electricity
│ │ ├── PowerTs_0_1.hpp
│ │ ├── PowerTs_1_0.hpp
│ │ ├── Power_0_1.hpp
│ │ ├── Power_1_0.hpp
│ │ ├── SourceTs_1_0.hpp
│ │ └── Source_1_0.hpp
│ ├── kinematics
│ │ ├── DoF2ndTs_0_1.hpp
│ │ ├── DoF2ndTs_1_0.hpp
│ │ ├── DoF2nd_0_1.hpp
│ │ ├── DoF2nd_1_0.hpp
│ │ ├── DoF3rdTs_0_1.hpp
│ │ ├── DoF3rdTs_1_0.hpp
│ │ ├── DoF3rdVarTs_1_0.hpp
│ │ ├── DoF3rd_0_1.hpp
│ │ ├── DoF3rd_1_0.hpp
│ │ ├── Velocity1VarTs_1_0.hpp
│ │ ├── Velocity3Var_1_0.hpp
│ │ ├── cartesian
│ │ │ ├── PointStateVarTs_0_1.hpp
│ │ │ ├── PointStateVar_0_1.hpp
│ │ │ ├── PointState_0_1.hpp
│ │ │ ├── PointVar_0_1.hpp
│ │ │ ├── Point_0_1.hpp
│ │ │ ├── PoseVarTs_0_1.hpp
│ │ │ ├── PoseVar_0_1.hpp
│ │ │ ├── Pose_0_1.hpp
│ │ │ ├── StateVarTs_0_1.hpp
│ │ │ ├── StateVar_0_1.hpp
│ │ │ ├── State_0_1.hpp
│ │ │ ├── TwistVarTs_0_1.hpp
│ │ │ ├── TwistVar_0_1.hpp
│ │ │ └── Twist_0_1.hpp
│ │ └── geodetic
│ │ │ ├── PointStateVarTs_0_1.hpp
│ │ │ ├── PointStateVar_0_1.hpp
│ │ │ ├── PointState_0_1.hpp
│ │ │ ├── PointVar_0_1.hpp
│ │ │ ├── Point_0_1.hpp
│ │ │ ├── PoseVar_0_1.hpp
│ │ │ ├── Pose_0_1.hpp
│ │ │ ├── StateVarTs_0_1.hpp
│ │ │ ├── StateVar_0_1.hpp
│ │ │ └── State_0_1.hpp
│ ├── optics
│ │ └── HighColor_0_1.hpp
│ ├── thermodynamics
│ │ └── PressureTempVarTs_0_1.hpp
│ └── time
│ │ ├── TAI64VarTs_0_1.hpp
│ │ ├── TAI64Var_0_1.hpp
│ │ └── TAI64_0_1.hpp
│ ├── primitive
│ ├── integer14
│ │ ├── Scalar_1_0.hpp
│ │ ├── Vector36_1_0.hpp
│ │ └── Vector4_1_0.hpp
│ ├── natural9
│ │ ├── Scalar_1_0.hpp
│ │ ├── Vector56_1_0.hpp
│ │ └── Vector6_1_0.hpp
│ ├── real16
│ │ ├── Scalar_1_0.hpp
│ │ ├── Vector2_1_0.hpp
│ │ ├── Vector31_1_0.hpp
│ │ ├── Vector3_1_0.hpp
│ │ ├── Vector4_1_0.hpp
│ │ ├── Vector6_1_0.hpp
│ │ └── Vector8_1_0.hpp
│ ├── real32
│ │ ├── Scalar_1_0.hpp
│ │ ├── Vector16_1_0.hpp
│ │ ├── Vector24_1_0.hpp
│ │ ├── Vector2_1_0.hpp
│ │ ├── Vector31_1_0.hpp
│ │ ├── Vector32_1_0.hpp
│ │ ├── Vector3_1_0.hpp
│ │ ├── Vector4_1_0.hpp
│ │ ├── Vector6_1_0.hpp
│ │ ├── Vector8_1_0.hpp
│ │ └── Vector9_1_0.hpp
│ └── zX005FzX005F1_0.hpp
│ ├── service
│ ├── Heartbeat_1_0.hpp
│ ├── Readiness_1_0.hpp
│ └── actuator
│ │ ├── FaultFlags_1_0.hpp
│ │ ├── Feedback_1_0.hpp
│ │ └── Status_1_0.hpp
│ └── telega
│ ├── CompactFeedback_0_1.hpp
│ ├── CompactFeedback_1_0.hpp
│ ├── DQ_0_1.hpp
│ ├── DQ_1_0.hpp
│ ├── ServoCommand_0_1.hpp
│ ├── ServoCommand_1_0.hpp
│ ├── Temperatures_0_1.hpp
│ ├── Temperatures_1_0.hpp
│ └── setpoint
│ ├── Raw14x36_0_1.hpp
│ ├── Raw14x4_0_1.hpp
│ ├── Raw9x56_0_1.hpp
│ └── Raw9x6_0_1.hpp
└── util
├── nodeinfo
├── NodeInfo.hpp
└── NodeInfoBase.hpp
├── port
├── PortListPublisher.hpp
└── PortListPublisherBase.hpp
├── registry
├── Registry.hpp
├── cavl.hpp
├── registry_base.hpp
├── registry_impl.hpp
└── registry_value.hpp
├── storage
├── KeyValueStorage.hpp
└── register_storage.hpp
└── transfer_metadata.hpp
/.github/dependabot.yml:
--------------------------------------------------------------------------------
1 | # See: https://docs.github.com/code-security/dependabot/dependabot-version-updates/configuration-options-for-the-dependabot.yml-file#about-the-dependabotyml-file
2 | version: 2
3 |
4 | updates:
5 | # Configure check for outdated GitHub Actions actions in workflows.
6 | # Source: https://github.com/arduino/tooling-project-assets/blob/main/workflow-templates/assets/dependabot/README.md
7 | # See: https://docs.github.com/code-security/dependabot/working-with-dependabot/keeping-your-actions-up-to-date-with-dependabot
8 | - package-ecosystem: github-actions
9 | directory: / # Check the repository's workflows under /.github/workflows/
10 | schedule:
11 | interval: daily
12 | labels:
13 | - "topic: ci"
14 |
--------------------------------------------------------------------------------
/.github/workflows/arduino-lint.yml:
--------------------------------------------------------------------------------
1 | name: Arduino Lint
2 | on:
3 | push:
4 | pull_request:
5 | # Scheduled trigger checks for breakage caused by new rules added to Arduino Lint
6 | schedule:
7 | # run every Saturday at 3 AM UTC
8 | - cron: "0 3 * * 6"
9 | # See: https://docs.github.com/en/free-pro-team@latest/actions/reference/events-that-trigger-workflows#workflow_dispatch
10 | workflow_dispatch:
11 | # See: https://docs.github.com/en/free-pro-team@latest/actions/reference/events-that-trigger-workflows#repository_dispatch
12 | repository_dispatch:
13 |
14 | jobs:
15 | lint:
16 | runs-on: ubuntu-latest
17 |
18 | steps:
19 | - name: Checkout
20 | uses: actions/checkout@v4
21 |
22 | - name: Arduino Lint
23 | uses: arduino/arduino-lint-action@v2
24 | with:
25 | project-type: library
26 | library-manager: update
27 |
--------------------------------------------------------------------------------
/.github/workflows/compile-examples.yml:
--------------------------------------------------------------------------------
1 | name: Compile Examples
2 |
3 | on:
4 | pull_request:
5 | paths:
6 | - ".github/workflows/compile-examples.yml"
7 | - "examples/**"
8 | - "src/**"
9 | push:
10 | paths:
11 | - ".github/workflows/compile-examples.yml"
12 | - "examples/**"
13 | - "src/**"
14 |
15 | jobs:
16 | build:
17 | runs-on: ubuntu-latest
18 |
19 | env:
20 | SKETCHES_REPORTS_PATH: sketches-reports
21 | LIBRARIES: |
22 | # Install the library from the local path.
23 | - source-path: ./
24 | - name: 107-Arduino-Debug
25 | - name: 107-Arduino-MCP2515
26 | - name: 107-Arduino-UniqueId
27 | - name: 107-Arduino-CriticalSection
28 |
29 | strategy:
30 | fail-fast: false
31 |
32 | matrix:
33 | board:
34 | - fqbn: rp2040:rp2040:arduino_nano_connect
35 | platforms: |
36 | - name: rp2040:rp2040
37 | source-url: https://github.com/earlephilhower/arduino-pico/releases/download/global/package_rp2040_index.json
38 | artifact-name-suffix: rp2040-arduino-nano-connect
39 | - fqbn: rp2040:rp2040:rpipico
40 | platforms: |
41 | - name: rp2040:rp2040
42 | source-url: https://github.com/earlephilhower/arduino-pico/releases/download/global/package_rp2040_index.json
43 | artifact-name-suffix: rp2040-rpipico
44 | - fqbn: arduino:renesas_portenta:portenta_c33
45 | platforms: |
46 | - name: arduino:renesas_portenta
47 | artifact-name-suffix: renesas-portenta-portenta-c33
48 | - fqbn: arduino:renesas_uno:minima
49 | platforms: |
50 | - name: arduino:renesas_uno
51 | artifact-name-suffix: renesas-uno-minima
52 |
53 | steps:
54 | - name: Checkout
55 | uses: actions/checkout@v4
56 |
57 | - name: Compile examples
58 | uses: arduino/compile-sketches@v1
59 | with:
60 | fqbn: ${{ matrix.board.fqbn }}
61 | platforms: ${{ matrix.board.platforms }}
62 | libraries: ${{ env.LIBRARIES }}
63 | enable-deltas-report: true
64 | github-token: ${{ secrets.GITHUB_TOKEN }}
65 | sketches-report-path: ${{ env.SKETCHES_REPORTS_PATH }}
66 | sketch-paths: |
67 | - examples/CAN/OpenCyphal-Blink
68 | - examples/CAN/OpenCyphal-Heartbeat-Publisher
69 | - examples/CAN/OpenCyphal-Heartbeat-Subscriber
70 | - examples/CAN/OpenCyphal-Service-Client
71 | - examples/CAN/OpenCyphal-Service-Server
72 |
73 | - name: Save memory usage change report as artifact
74 | if: github.event_name == 'pull_request'
75 | uses: actions/upload-artifact@v4
76 | with:
77 | if-no-files-found: error
78 | path: ${{ env.SKETCHES_REPORTS_PATH }}
79 | name: sketches-report-${{ matrix.board.artifact-name-suffix }}
80 |
--------------------------------------------------------------------------------
/.github/workflows/extra-library-checks.yml:
--------------------------------------------------------------------------------
1 | name: Extra Library Checks
2 |
3 | on:
4 | - pull_request
5 | - push
6 |
7 | jobs:
8 | extra-library-checks:
9 | runs-on: ubuntu-latest
10 |
11 | env:
12 | ARDUINO_CI_SCRIPT_FOLDER: extras/ci-tools/arduino-ci-script
13 |
14 | steps:
15 | - name: Checkout
16 | uses: actions/checkout@v4
17 |
18 | - name: Install arduino-ci-script
19 | run: |
20 | # install arduino-ci-script
21 | git clone https://github.com/per1234/arduino-ci-script.git "$ARDUINO_CI_SCRIPT_FOLDER"
22 | cd "$ARDUINO_CI_SCRIPT_FOLDER"
23 | # Get new tags from the remote
24 | git fetch --tags
25 | # Checkout the latest tag
26 | git checkout $(git describe --tags `git rev-list --tags --max-count=1`)
27 |
28 | # See: https://github.com/per1234/arduino-ci-script#check_keywords_txt-searchpath-maximumsearchdepth
29 | - name: Check keywords.txt
30 | run: |
31 | source "${ARDUINO_CI_SCRIPT_FOLDER}/arduino-ci-script.sh"
32 | check_keywords_txt "$GITHUB_WORKSPACE"
33 |
--------------------------------------------------------------------------------
/.github/workflows/general-formatting-checks.yml:
--------------------------------------------------------------------------------
1 | name: General Formatting Checks
2 |
3 | on:
4 | - pull_request
5 | - push
6 |
7 | jobs:
8 | general-formatting-checks:
9 | runs-on: ubuntu-latest
10 |
11 | steps:
12 | - name: Checkout repository
13 | uses: actions/checkout@v4
14 |
15 | # https://github.com/per1234/formatting-checks
16 | - name: Check for files starting with a blank line
17 | run: find . -path './.git' -prune -or -path './src/types' -prune -or -path './libcanard' -prune -or -path './extras/test/external' -prune -or -type f -print0 | xargs -0 -L1 bash -c 'tail -1 "$0" | grep --binary-files=without-match --regexp="^$"; if [[ "$?" == "0" ]]; then echo "Blank line found at end of $0."; false; fi'
18 |
19 | - name: Check for unnecessary use of true tabs
20 | run: find . -path './.git' -prune -or -path './libcanard' -prune -or -path './extras/test/external' -prune -or \( -not -name 'keywords.txt' -and -not -name '.gitmodules' -and -type f \) -exec grep --with-filename --line-number --binary-files=without-match --regexp=$'\t' '{}' \; -exec echo 'Tab found.' \; -exec false '{}' +
21 |
22 | - name: Check for trailing whitespace
23 | run: find . -path './.git' -prune -or -path './libcanard' -prune -or -path './src/DSDL_Types.h.impl' -prune -or -path './extras/test/external' -prune -or -type f -exec grep --with-filename --line-number --binary-files=without-match --regexp='[[:blank:]]$' '{}' \; -exec echo 'Trailing whitespace found.' \; -exec false '{}' +
24 |
25 | - name: Check for non-Unix line endings
26 | run: find . -path './.git' -prune -or -path './libcanard' -prune -or -path './extras/test/external' -prune -or -type f -exec grep --files-with-matches --binary-files=without-match --regexp=$'\r$' '{}' \; -exec echo 'Non-Unix EOL detected.' \; -exec false '{}' +
27 |
28 | - name: Check for blank lines at end of files
29 | run: find . -path './.git' -prune -or -path './src/types' -prune -or -path './src/DSDL_Types.h.impl' -prune -or -path './libcanard' -prune -or -path './extras/test/external' -prune -or -type f -print0 | xargs -0 -L1 bash -c 'tail -1 "$0" | grep --binary-files=without-match --regexp="^$"; if [[ "$?" == "0" ]]; then echo "Blank line found at end of $0."; false; fi'
30 |
31 | - name: Check for files that don't end in a newline
32 | # https://stackoverflow.com/a/25686825
33 | run: find . -path './.git' -prune -or -path './src/types' -prune -or -path './libcanard' -prune -or -path './extras/test/external' -prune -or -type f -print0 | xargs -0 -L1 bash -c 'if test "$(grep --files-with-matches --binary-files=without-match --max-count=1 --regexp='.*' "$0")" && test "$(tail --bytes=1 "$0")"; then echo "No new line at end of $0."; false; fi'
34 |
--------------------------------------------------------------------------------
/.github/workflows/report-size-deltas.yml:
--------------------------------------------------------------------------------
1 | name: Report Size Deltas
2 |
3 | on:
4 | schedule:
5 | - cron: '*/5 * * * *'
6 |
7 | jobs:
8 | report:
9 | runs-on: ubuntu-latest
10 |
11 | steps:
12 | # See: https://github.com/arduino/report-size-deltas/README.md
13 | uses: arduino/report-size-deltas@v1
14 | with:
15 | # Regex matching the names of the workflow artifacts created by the "Compile Examples" workflow
16 | sketches-reports-source: ^sketches-report-.+
17 |
--------------------------------------------------------------------------------
/.github/workflows/smoke-test.yml:
--------------------------------------------------------------------------------
1 | name: Build
2 |
3 | # See: https://docs.github.com/en/actions/reference/events-that-trigger-workflows
4 | on:
5 | push:
6 | pull_request:
7 | schedule:
8 | # Run every Tuesday at 8 AM UTC
9 | - cron: "0 8 * * TUE"
10 | workflow_dispatch:
11 | repository_dispatch:
12 |
13 | permissions:
14 | contents: read
15 |
16 | jobs:
17 | smoke-test:
18 | runs-on: ubuntu-latest
19 |
20 | steps:
21 | - name: Checkout repository
22 | uses: actions/checkout@v4
23 |
24 | - name: Install CMake
25 | run: sudo apt-get install cmake
26 |
27 | - name: Create build directory, run CMake and Make
28 | run: mkdir build && cd build && cmake -DBUILD_EXAMPLES=ON .. && make
29 |
--------------------------------------------------------------------------------
/.github/workflows/spell-check.yml:
--------------------------------------------------------------------------------
1 | name: Spell Check
2 |
3 | on:
4 | - pull_request
5 | - push
6 |
7 | jobs:
8 | spellcheck:
9 | runs-on: ubuntu-latest
10 |
11 | steps:
12 | - name: Checkout repository
13 | uses: actions/checkout@v4
14 |
15 | # See: https://github.com/codespell-project/actions-codespell/blob/master/README.md
16 | - name: Spell check
17 | uses: codespell-project/actions-codespell@master
18 | with:
19 | check_filenames: true
20 | check_hidden: true
21 | skip: ./.git,./extras/test/external,./src/lib,./src/libcanard,./src/libo1heap,./src/types,
22 | ignore_words_file: extras/codespell-ignore-words-list.txt
23 |
--------------------------------------------------------------------------------
/.github/workflows/sync-labels.yml:
--------------------------------------------------------------------------------
1 | # Source: https://github.com/arduino/tooling-project-assets/blob/main/workflow-templates/sync-labels.md
2 | name: Sync Labels
3 |
4 | # See: https://docs.github.com/en/actions/reference/events-that-trigger-workflows
5 | on:
6 | push:
7 | paths:
8 | - ".github/workflows/sync-labels.ya?ml"
9 | - ".github/label-configuration-files/*.ya?ml"
10 | pull_request:
11 | paths:
12 | - ".github/workflows/sync-labels.ya?ml"
13 | - ".github/label-configuration-files/*.ya?ml"
14 | schedule:
15 | # run every Tuesday at 3 AM UTC
16 | - cron: "0 3 * * 2"
17 | workflow_dispatch:
18 | repository_dispatch:
19 |
20 | env:
21 | CONFIGURATIONS_FOLDER: .github/label-configuration-files
22 | CONFIGURATIONS_ARTIFACT: label-configuration-files
23 |
24 | jobs:
25 | check:
26 | runs-on: ubuntu-latest
27 |
28 | steps:
29 | - name: Checkout repository
30 | uses: actions/checkout@v4
31 |
32 | - name: Download JSON schema for labels configuration file
33 | id: download-schema
34 | uses: carlosperate/download-file-action@v2.0.2
35 | with:
36 | file-url: https://raw.githubusercontent.com/arduino/tooling-project-assets/main/workflow-templates/assets/sync-labels/arduino-tooling-gh-label-configuration-schema.json
37 | location: ${{ runner.temp }}/label-configuration-schema
38 |
39 | - name: Install JSON schema validator
40 | run: |
41 | sudo npm install \
42 | --global \
43 | ajv-cli \
44 | ajv-formats
45 |
46 | - name: Validate local labels configuration
47 | run: |
48 | # See: https://github.com/ajv-validator/ajv-cli#readme
49 | ajv validate \
50 | --all-errors \
51 | -c ajv-formats \
52 | -s "${{ steps.download-schema.outputs.file-path }}" \
53 | -d "${{ env.CONFIGURATIONS_FOLDER }}/*.{yml,yaml}"
54 |
55 | download:
56 | needs: check
57 | runs-on: ubuntu-latest
58 |
59 | strategy:
60 | matrix:
61 | filename:
62 | # Filenames of the shared configurations to apply to the repository in addition to the local configuration.
63 | # https://github.com/107-systems/.github/blob/main/workflow-templates/assets/sync-labels
64 | - universal.yml
65 |
66 | steps:
67 | - name: Download
68 | uses: carlosperate/download-file-action@v2.0.2
69 | with:
70 | file-url: https://raw.githubusercontent.com/107-systems/.github/main/workflow-templates/assets/sync-labels/${{ matrix.filename }}
71 |
72 | - name: Pass configuration files to next job via workflow artifact
73 | uses: actions/upload-artifact@v4
74 | with:
75 | path: |
76 | *.yaml
77 | *.yml
78 | if-no-files-found: error
79 | name: ${{ env.CONFIGURATIONS_ARTIFACT }}
80 |
81 | sync:
82 | needs: download
83 | runs-on: ubuntu-latest
84 |
85 | steps:
86 | - name: Set environment variables
87 | run: |
88 | # See: https://docs.github.com/en/actions/reference/workflow-commands-for-github-actions#setting-an-environment-variable
89 | echo "MERGED_CONFIGURATION_PATH=${{ runner.temp }}/labels.yml" >> "$GITHUB_ENV"
90 |
91 | - name: Determine whether to dry run
92 | id: dry-run
93 | if: >
94 | github.event == 'pull_request' ||
95 | github.ref != format('refs/heads/{0}', github.event.repository.default_branch)
96 | run: |
97 | # Use of this flag in the github-label-sync command will cause it to only check the validity of the
98 | # configuration.
99 | echo "::set-output name=flag::--dry-run"
100 |
101 | - name: Checkout repository
102 | uses: actions/checkout@v4
103 |
104 | - name: Download configuration files artifact
105 | uses: actions/download-artifact@v4
106 | with:
107 | name: ${{ env.CONFIGURATIONS_ARTIFACT }}
108 | path: ${{ env.CONFIGURATIONS_FOLDER }}
109 |
110 | - name: Remove unneeded artifact
111 | uses: geekyeggo/delete-artifact@v5
112 | with:
113 | name: ${{ env.CONFIGURATIONS_ARTIFACT }}
114 |
115 | - name: Merge label configuration files
116 | run: |
117 | # Merge all configuration files
118 | shopt -s extglob
119 | cat "${{ env.CONFIGURATIONS_FOLDER }}"/*.@(yml|yaml) > "${{ env.MERGED_CONFIGURATION_PATH }}"
120 |
121 | - name: Install github-label-sync
122 | run: sudo npm install --global github-label-sync
123 |
124 | - name: Sync labels
125 | env:
126 | GITHUB_ACCESS_TOKEN: ${{ secrets.GITHUB_TOKEN }}
127 | run: |
128 | # See: https://github.com/Financial-Times/github-label-sync
129 | github-label-sync \
130 | --labels "${{ env.MERGED_CONFIGURATION_PATH }}" \
131 | ${{ steps.dry-run.outputs.flag }} \
132 | ${{ github.repository }}
133 |
--------------------------------------------------------------------------------
/.github/workflows/unit-tests.yml:
--------------------------------------------------------------------------------
1 | name: Unit Tests
2 |
3 | on:
4 | pull_request:
5 | paths:
6 | - ".github/workflows/unit-tests.yml"
7 | - 'extras/test/**'
8 | - 'src/**'
9 |
10 | push:
11 | paths:
12 | - ".github/workflows/unit-tests.yml"
13 | - 'extras/test/**'
14 | - 'src/**'
15 |
16 | jobs:
17 | test:
18 | name: Run unit tests
19 | runs-on: ubuntu-latest
20 |
21 | env:
22 | COVERAGE_DATA_PATH: extras/coverage-data/coverage.info
23 |
24 | steps:
25 | - name: Checkout
26 | uses: actions/checkout@v4
27 |
28 | - uses: arduino/cpp-test-action@main
29 | with:
30 | runtime-paths: |
31 | - extras/test/build/bin/test_cyphal++
32 | coverage-exclude-paths: |
33 | - '*/extras/test/*'
34 | - '/usr/*'
35 | coverage-data-path: ${{ env.COVERAGE_DATA_PATH }}
36 |
37 | - name: Upload coverage report to Codecov
38 | uses: codecov/codecov-action@v5
39 | with:
40 | token: ${{ secrets.CODECOV_TOKEN }}
41 | file: "${{ env.COVERAGE_DATA_PATH }}"
42 | fail_ci_if_error: true
43 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | .vscode/
2 | .idea/
3 | build/
4 | cmake-build-debug/
5 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | ##########################################################################
2 | cmake_minimum_required(VERSION 3.8)
3 | ##########################################################################
4 | project("cyphal++")
5 | ##########################################################################
6 | if(CMAKE_C_COMPILER_ID STREQUAL "GNU" AND CMAKE_C_COMPILER_VERSION VERSION_LESS 11)
7 | message(WARNING "GNU C compiler version ${CMAKE_C_COMPILER_VERSION} is too old and is unsupported. Version 11+ is required.")
8 | endif()
9 | if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 11)
10 | message(WARNING "GNU C++ compiler version ${CMAKE_CXX_COMPILER_VERSION} is too old and is unsupported. Version 11+ is required.")
11 | endif()
12 | ##########################################################################
13 | set(CMAKE_VERBOSE_MAKEFILE OFF)
14 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
15 | ##########################################################################
16 | option(BUILD_EXAMPLES "Build all examples provided with this library" OFF)
17 | ##########################################################################
18 | add_library(${PROJECT_NAME} STATIC
19 | src/Node.cpp
20 | src/libcanard/canard.c
21 | src/libo1heap/o1heap.c
22 | )
23 | ##########################################################################
24 | target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic -Werror)
25 | ##########################################################################
26 | target_include_directories(${PROJECT_NAME} PRIVATE src extras/cyphal++/include src/libcanard src/libo1heap)
27 | target_include_directories(${PROJECT_NAME} SYSTEM INTERFACE src extras/cyphal++/include src/libcanard src/libo1heap)
28 | target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_20)
29 | ##########################################################################
30 | if(BUILD_EXAMPLES)
31 | add_subdirectory(examples/CAN/host-example-01-opencyphal-basic-node)
32 | endif()
33 | ##########################################################################
34 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2020 Alexander Entinger, LXRobotics GmbH
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 |
2 | :floppy_disk: `107-Arduino-Cyphal`
3 | ==================================
4 |
5 | [](https://www.ardu-badge.com/107-Arduino-Cyphal)
6 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions?workflow=Compile+Examples)
7 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions/workflows/smoke-test.yml)
8 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions?workflow=Unit+Tests)
9 | [](https://codecov.io/gh/107-systems/107-Arduino-Cyphal)
10 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions?workflow=Arduino+Lint)
11 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions?workflow=Extra+Library+Checks)
12 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions?workflow=General+Formatting+Checks)
13 | [](https://github.com/107-systems/107-Arduino-Cyphal/actions?workflow=Spell+Check)
14 |
15 | This Arduino library implements the [Cyphal](https://opencyphal.org/) protocol ([v1.0-beta](https://opencyphal.org/specification/Cyphal_Specification.pdf)) utilizing [libcanard](https://github.com/OpenCyphal/libcanard).
16 |
17 | **Note**: For commercial support, customisation or contract development contact consulting@lxrobotics.com.
18 |
19 |
20 |
21 |
22 |
23 |
24 | This library works for
25 | * [arduino-pico](https://github.com/earlephilhower/arduino-pico): [`Raspberry Pi Pico`](https://www.raspberrypi.org/products/raspberry-pi-pico), `Adafruit Feather RP2040`, ... :heavy_check_mark:
26 | ```bash
27 | arduino-cli compile -b rp2040:rp2040:rpipico -v examples/OpenCyphal-Heartbeat-Publisher -u -p /dev/ttyACM0
28 | ```
29 | * [ArduinoCore-renesas](https://github.com/arduino/ArduinoCore-renesas): [`Portenta C33`](https://store.arduino.cc/products/portenta-c33), [`Uno R4 WiFi`](https://store.arduino.cc/products/uno-r4-wifi), [`Uno R4 Minima`](https://store.arduino.cc/products/uno-r4-minima), ... :heavy_check_mark:
30 | ```bash
31 | arduino-cli compile -b arduino:renesas_portenta:portenta_c33 -v examples/OpenCyphal-Heartbeat-Publisher -u -p /dev/ttyACM0
32 | ```
33 | * **Host** (x86/x64/...): Using the CMake build system this library can be cross-compiled to a static C++ library and linked against any C++ executable. This is possible because the code itself is pure C/C++ without and dependencies to the Arduino framework.
34 | ```bash
35 | git clone https://github.com/107-systems/107-Arduino-Cyphal && cd 107-Arduino-Cyphal
36 | mkdir build && cd build
37 | cmake .. && make
38 | ```
39 | or
40 | ```bash
41 | cmake -DBUILD_EXAMPLES=ON .. && make
42 | ```
43 |
44 | ### Reference-Implementations
45 | * [CyphalPicoBase/CAN-firmware](https://github.com/107-systems/CyphalPicoBase-CAN-firmware): Firmware for the [CyphalPicoBase/CAN](https://github.com/generationmake/CyphalPicoBase-CAN) board.
46 | * [CyphalServoController12/CAN-firmware](https://github.com/107-systems/CyphalServoController12-CAN-firmware): Firmware for the [CyphalServoController12/CAN](https://github.com/generationmake/OpenCyphalServoController12) board.
47 | * [CyphalRobotController07/CAN-firmware](https://github.com/107-systems/CyphalRobotController07-CAN-firmware): Firmware for the [CyphalRobotController07/CAN](https://github.com/generationmake/CyphalRobotController07-CAN) board.
48 | * [l3xz-aux-ctrl-firmware](https://github.com/107-systems/l3xz-aux-ctrl-firmware): Firmware for the [L3X-Z](https://github.com/107-systems/l3xz) auxiliary controller ([CyphalPicoBase/CAN](https://github.com/generationmake/CyphalPicoBase-CAN)).
49 | * [l3xz-leg-ctrl-firmware](https://github.com/107-systems/l3xz-leg-ctrl-firmware): Firmware for the [L3X-Z](https://github.com/107-systems/l3xz) leg controller ([l3xz-leg-ctrl-hardware](https://github.com/107-systems/l3xz-leg-ctrl-hardware)).
50 | * [l3xz-radiation-sensor-firmware](https://github.com/107-systems/l3xz-radiation-sensor-firmware): Firmware for the [L3X-Z](https://github.com/107-systems/l3xz) radiation sensor ([CyphalPicoBase/CAN](https://github.com/generationmake/CyphalPicoBase-CAN)).
51 | * [l3xz-pressure-sensor-firmware](https://github.com/107-systems/l3xz-pressure-sensor-firmware): Firmware for the [L3X-Z](https://github.com/107-systems/l3xz) pressure sensor ([CyphalPicoBase/CAN](https://github.com/generationmake/CyphalPicoBase-CAN)).
52 |
53 | ### Examples
54 | #### Publisher
55 | ```C++
56 | #include <107-Arduino-Cyphal.h>
57 | /* ... */
58 | cyphal::Node::Heap node_heap;
59 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
60 |
61 | cyphal::Publisher heartbeat_pub = node_hdl.create_publisher
62 | (1*1000*1000UL /* = 1 sec in usecs. */);
63 | /* ... */
64 | void loop() {
65 | /* Process all pending OpenCyphal actions. */
66 | node_hdl.spinSome();
67 | /* ... */
68 | uavcan::node::Heartbeat_1_0 msg;
69 |
70 | msg.uptime = now / 1000;
71 | msg.health.value = uavcan::node::Health_1_0::NOMINAL;
72 | msg.mode.value = uavcan::node::Mode_1_0::OPERATIONAL;
73 | msg.vendor_specific_status_code = 0;
74 |
75 | heartbeat_pub->publish(msg);
76 | /* ... */
77 | }
78 | ```
79 |
80 | #### Subscriber
81 | ```C++
82 | #include <107-Arduino-Cyphal.h>
83 | /* ... */
84 | cyphal::Node::Heap node_heap;
85 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
86 |
87 | cyphal::Subscription heartbeat_subscription = node_hdl.create_subscription(onHeartbeat_1_0_Received);
88 | /* ... */
89 | void loop() {
90 | /* Process all pending OpenCyphal actions. */
91 | node_hdl.spinSome();
92 | }
93 | /* ... */
94 | void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg)
95 | {
96 | char msg_buf[64];
97 | snprintf(msg_buf, sizeof(msg_buf),
98 | "Uptime = %d, Health = %d, Mode = %d, VSSC = %d",
99 | msg.uptime, msg.health.value, msg.mode.value, msg.vendor_specific_status_code);
100 | Serial.println(msg_buf);
101 | }
102 | ```
103 |
104 | #### Service Server
105 | ```C++
106 | #include <107-Arduino-Cyphal.h>
107 | /* ... */
108 | cyphal::Node::Heap node_heap;
109 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
110 |
111 | cyphal::ServiceServer execute_command_srv = node_hdl.create_service_server
112 | (2*1000*1000UL, onExecuteCommand_1_1_Request_Received);
113 | /* ... */
114 | void loop() {
115 | /* Process all pending OpenCyphal actions. */
116 | node_hdl.spinSome();
117 | }
118 | /* ... */
119 | ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(ExecuteCommand::Request_1_1 const & req)
120 | {
121 | ExecuteCommand::Response_1_1 rsp;
122 | rsp.status = ExecuteCommand::Response_1_1::STATUS_SUCCESS;
123 | return rsp;
124 | }
125 | ```
126 |
127 | #### Service Client
128 | ```C++
129 | #include <107-Arduino-Cyphal.h>
130 | /* ... */
131 | cyphal::Node::Heap node_heap;
132 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { /* ... */ });
133 |
134 | cyphal::ServiceClient srv_client = node_hdl.create_service_client
135 | (2*1000*1000UL, onExecuteCommand_1_1_Response_Received);
136 | /* ... */
137 | void setup() {
138 | ExecuteCommand::Request_1_1 req;
139 | req.command = 0xCAFE;
140 |
141 | if (!srv_client->request(27 /* remote node id */, req))
142 | Serial.println("Service request failed.");
143 | }
144 | void loop() {
145 | /* Process all pending OpenCyphal actions. */
146 | node_hdl.spinSome();
147 | }
148 | /* ... */
149 | void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp)
150 | {
151 | if (rsp.status == ExecuteCommand::Response_1_1::STATUS_SUCCESS)
152 | Serial.println("Response: Success");
153 | else
154 | Serial.println("Response: Error");
155 | }
156 | ```
157 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Blink/OpenCyphal-Blink.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example creates a OpenCyphal node. The builtin LED can be switched on and off using OpenCyphal.
3 | * It also shows periodic transmission of a OpenCyphal heartbeat message via CAN.
4 | *
5 | * switch built in LED on with
6 | * yakut -i 'CAN(can.media.socketcan.SocketCANMedia("can0",8),59)' pub 1620.uavcan.primitive.scalar.Bit.1.0 'value: true'
7 | *
8 | * switch built in LED off with
9 | * yakut -i 'CAN(can.media.socketcan.SocketCANMedia("can0",8),59)' pub 1620.uavcan.primitive.scalar.Bit.1.0 'value: false'
10 | */
11 |
12 | /**************************************************************************************
13 | * INCLUDE
14 | **************************************************************************************/
15 |
16 | #include
17 |
18 | #include <107-Arduino-Cyphal.h>
19 | #include <107-Arduino-MCP2515.h>
20 | #include <107-Arduino-CriticalSection.h>
21 | #if defined(ARDUINO_EDGE_CONTROL)
22 | # include
23 | #endif
24 |
25 | /**************************************************************************************
26 | * NAMESPACE
27 | **************************************************************************************/
28 |
29 | using namespace uavcan::node;
30 | using namespace uavcan::primitive::scalar;
31 |
32 | /**************************************************************************************
33 | * CONSTANTS
34 | **************************************************************************************/
35 |
36 | static int const MKRCAN_MCP2515_CS_PIN = 3;
37 | static int const MKRCAN_MCP2515_INT_PIN = 7;
38 | static CanardPortID const BIT_PORT_ID = 1620U;
39 |
40 | /**************************************************************************************
41 | * FUNCTION DECLARATION
42 | **************************************************************************************/
43 |
44 | void onReceiveBufferFull(CanardFrame const &);
45 | void onBit_1_0_Received (Bit_1_0 const & msg);
46 |
47 | /**************************************************************************************
48 | * GLOBAL VARIABLES
49 | **************************************************************************************/
50 |
51 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
52 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
53 | [](uint8_t const data) { return SPI.transfer(data); },
54 | micros,
55 | onReceiveBufferFull,
56 | nullptr);
57 |
58 | cyphal::Node::Heap node_heap;
59 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
60 |
61 | cyphal::Publisher heartbeat_pub = node_hdl.create_publisher
62 | (1*1000*1000UL /* = 1 sec in usecs. */);
63 | cyphal::Subscription bit_subscription = node_hdl.create_subscription
64 | (BIT_PORT_ID, onBit_1_0_Received);
65 |
66 | /**************************************************************************************
67 | * SETUP/LOOP
68 | **************************************************************************************/
69 |
70 | void setup()
71 | {
72 | Serial.begin(9600);
73 | while(!Serial) { }
74 |
75 | /* Setup LED and initialize */
76 | #if defined(ARDUINO_EDGE_CONTROL)
77 | Power.on(PWR_3V3);
78 | Power.on(PWR_VBAT);
79 | if (!Expander.begin())
80 | {
81 | Serial.println("Arduino Edge Control - Expander.begin() failed");
82 | for(;;) { }
83 | Expander.pinMode(EXP_LED1, OUTPUT);
84 | }
85 | #else
86 | pinMode(LED_BUILTIN, OUTPUT);
87 | digitalWrite(LED_BUILTIN, LOW);
88 | #endif
89 |
90 | /* Setup SPI access */
91 | SPI.begin();
92 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
93 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
94 |
95 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
96 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
97 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
98 |
99 | /* Initialize MCP2515 */
100 | mcp2515.begin();
101 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
102 | mcp2515.setNormalMode();
103 | }
104 |
105 | void loop()
106 | {
107 | /* Process all pending OpenCyphal actions.
108 | */
109 | {
110 | CriticalSection crit_sec;
111 | node_hdl.spinSome();
112 | }
113 |
114 | static unsigned long prev = 0;
115 | unsigned long const now = millis();
116 |
117 | /* Publish the heartbeat once/second */
118 | if(now - prev > 1000)
119 | {
120 | prev = now;
121 |
122 | uavcan::node::Heartbeat_1_0 msg;
123 |
124 | msg.uptime = now / 1000;
125 | msg.health.value = uavcan::node::Health_1_0::NOMINAL;
126 | msg.mode.value = uavcan::node::Mode_1_0::OPERATIONAL;
127 | msg.vendor_specific_status_code = 0;
128 |
129 | heartbeat_pub->publish(msg);
130 | }
131 | }
132 |
133 | /**************************************************************************************
134 | * FUNCTION DEFINITION
135 | **************************************************************************************/
136 |
137 | void onReceiveBufferFull(CanardFrame const & frame)
138 | {
139 | node_hdl.onCanFrameReceived(frame);
140 | }
141 |
142 | void onBit_1_0_Received(Bit_1_0 const & msg)
143 | {
144 | if(msg.value)
145 | {
146 | #if defined(ARDUINO_EDGE_CONTROL)
147 | Expander.digitalWrite(EXP_LED1, LOW);
148 | #else
149 | digitalWrite(LED_BUILTIN, HIGH);
150 | #endif
151 | Serial.println("Received Bit: true");
152 | }
153 | else
154 | {
155 | #if defined(ARDUINO_EDGE_CONTROL)
156 | Expander.digitalWrite(EXP_LED1, HIGH);
157 | #else
158 | digitalWrite(LED_BUILTIN, LOW);
159 | #endif
160 | Serial.println("Received Bit: false");
161 | }
162 | }
163 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Heartbeat-Publisher/OpenCyphal-Heartbeat-Publisher.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example shows periodic transmission of a OpenCyphal heartbeat message via CAN.
3 | */
4 |
5 | /**************************************************************************************
6 | * INCLUDE
7 | **************************************************************************************/
8 |
9 | #include
10 |
11 | #include <107-Arduino-Cyphal.h>
12 | #include <107-Arduino-MCP2515.h>
13 | #include <107-Arduino-CriticalSection.h>
14 |
15 | /**************************************************************************************
16 | * NAMESPACE
17 | **************************************************************************************/
18 |
19 | using namespace uavcan::node;
20 |
21 | /**************************************************************************************
22 | * CONSTANTS
23 | **************************************************************************************/
24 |
25 | static int const MKRCAN_MCP2515_CS_PIN = 3;
26 | static int const MKRCAN_MCP2515_INT_PIN = 7;
27 |
28 | /**************************************************************************************
29 | * GLOBAL VARIABLES
30 | **************************************************************************************/
31 |
32 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
33 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
34 | [](uint8_t const data) { return SPI.transfer(data); },
35 | micros,
36 | nullptr,
37 | nullptr);
38 |
39 | cyphal::Node::Heap node_heap;
40 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
41 |
42 | cyphal::Publisher heartbeat_pub = node_hdl.create_publisher
43 | (1*1000*1000UL /* = 1 sec in usecs. */);
44 |
45 | /**************************************************************************************
46 | * SETUP/LOOP
47 | **************************************************************************************/
48 |
49 | void setup()
50 | {
51 | Serial.begin(9600);
52 | while(!Serial) { }
53 |
54 | /* Setup SPI access */
55 | SPI.begin();
56 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
57 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
58 |
59 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
60 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
61 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
62 |
63 | /* Initialize MCP2515 */
64 | mcp2515.begin();
65 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
66 | mcp2515.setNormalMode();
67 | }
68 |
69 | void loop()
70 | {
71 | /* Process all pending OpenCyphal actions.
72 | */
73 | {
74 | CriticalSection crit_sec;
75 | node_hdl.spinSome();
76 | }
77 |
78 | /* Publish the heartbeat once/second */
79 | static unsigned long prev = 0;
80 | unsigned long const now = millis();
81 | if(now - prev > 1000)
82 | {
83 | prev = now;
84 |
85 | uavcan::node::Heartbeat_1_0 msg;
86 |
87 | msg.uptime = now / 1000;
88 | msg.health.value = uavcan::node::Health_1_0::NOMINAL;
89 | msg.mode.value = uavcan::node::Mode_1_0::OPERATIONAL;
90 | msg.vendor_specific_status_code = 0;
91 |
92 | heartbeat_pub->publish(msg);
93 | }
94 | }
95 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Heartbeat-Subscriber-With-Metadata/OpenCyphal-Heartbeat-Subscriber-With-Metadata.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example shows reception of a OpenCyphal heartbeat message via CAN.
3 | */
4 |
5 | /**************************************************************************************
6 | * INCLUDE
7 | **************************************************************************************/
8 |
9 | #include
10 |
11 | #include <107-Arduino-Cyphal.h>
12 | #include <107-Arduino-MCP2515.h>
13 | #include <107-Arduino-CriticalSection.h>
14 |
15 | /**************************************************************************************
16 | * NAMESPACE
17 | **************************************************************************************/
18 |
19 | using namespace uavcan::node;
20 |
21 | /**************************************************************************************
22 | * CONSTANTS
23 | **************************************************************************************/
24 |
25 | static int const MKRCAN_MCP2515_CS_PIN = 3;
26 | static int const MKRCAN_MCP2515_INT_PIN = 7;
27 |
28 | /**************************************************************************************
29 | * FUNCTION DECLARATION
30 | **************************************************************************************/
31 |
32 | void onReceiveBufferFull(CanardFrame const &);
33 | void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg, cyphal::TransferMetadata const & metadata);
34 |
35 | /**************************************************************************************
36 | * GLOBAL VARIABLES
37 | **************************************************************************************/
38 |
39 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
40 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
41 | [](uint8_t const data) { return SPI.transfer(data); },
42 | micros,
43 | onReceiveBufferFull,
44 | nullptr);
45 |
46 | cyphal::Node::Heap node_heap;
47 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
48 |
49 | cyphal::Subscription heartbeat_subscription = node_hdl.create_subscription(onHeartbeat_1_0_Received);
50 |
51 | /**************************************************************************************
52 | * SETUP/LOOP
53 | **************************************************************************************/
54 |
55 | void setup()
56 | {
57 | Serial.begin(9600);
58 | while(!Serial) { }
59 | delay(1000);
60 | Serial.println("|---- OpenCyphal Heartbeat Subscription With Metadata Example ----|");
61 |
62 | /* Setup SPI access */
63 | SPI.begin();
64 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
65 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
66 |
67 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
68 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
69 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
70 |
71 | /* Initialize MCP2515 */
72 | mcp2515.begin();
73 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
74 | mcp2515.setNormalMode();
75 |
76 | Serial.println("setup finished");
77 | }
78 |
79 | void loop()
80 | {
81 | /* Process all pending OpenCyphal actions.
82 | */
83 | {
84 | CriticalSection crit_sec;
85 | node_hdl.spinSome();
86 | }
87 | }
88 |
89 | /**************************************************************************************
90 | * FUNCTION DEFINITION
91 | **************************************************************************************/
92 |
93 | void onReceiveBufferFull(CanardFrame const & frame)
94 | {
95 | node_hdl.onCanFrameReceived(frame);
96 | }
97 |
98 | void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg, cyphal::TransferMetadata const & metadata)
99 | {
100 | char msg_buf[70];
101 | snprintf(
102 | msg_buf,
103 | sizeof(msg_buf),
104 | "Node ID= %d, Uptime = %d, Health = %d, Mode = %d, VSSC = %d",
105 | metadata.remote_node_id,
106 | msg.uptime,
107 | msg.health.value,
108 | msg.mode.value,
109 | msg.vendor_specific_status_code);
110 |
111 | Serial.println(msg_buf);
112 | }
113 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Heartbeat-Subscriber/OpenCyphal-Heartbeat-Subscriber.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example shows reception of a OpenCyphal heartbeat message via CAN.
3 | */
4 |
5 | /**************************************************************************************
6 | * INCLUDE
7 | **************************************************************************************/
8 |
9 | #include
10 |
11 | #include <107-Arduino-Cyphal.h>
12 | #include <107-Arduino-MCP2515.h>
13 | #include <107-Arduino-CriticalSection.h>
14 |
15 | /**************************************************************************************
16 | * NAMESPACE
17 | **************************************************************************************/
18 |
19 | using namespace uavcan::node;
20 |
21 | /**************************************************************************************
22 | * CONSTANTS
23 | **************************************************************************************/
24 |
25 | static int const MKRCAN_MCP2515_CS_PIN = 3;
26 | static int const MKRCAN_MCP2515_INT_PIN = 7;
27 |
28 | /**************************************************************************************
29 | * FUNCTION DECLARATION
30 | **************************************************************************************/
31 |
32 | void onReceiveBufferFull (CanardFrame const &);
33 | void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg);
34 |
35 | /**************************************************************************************
36 | * GLOBAL VARIABLES
37 | **************************************************************************************/
38 |
39 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
40 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
41 | [](uint8_t const data) { return SPI.transfer(data); },
42 | micros,
43 | onReceiveBufferFull,
44 | nullptr);
45 |
46 | cyphal::Node::Heap node_heap;
47 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
48 |
49 | cyphal::Subscription heartbeat_subscription = node_hdl.create_subscription(onHeartbeat_1_0_Received);
50 |
51 | /**************************************************************************************
52 | * SETUP/LOOP
53 | **************************************************************************************/
54 |
55 | void setup()
56 | {
57 | Serial.begin(9600);
58 | while(!Serial) { }
59 | delay(1000);
60 | Serial.println("|---- OpenCyphal Heartbeat Subscription Example ----|");
61 |
62 | /* Setup SPI access */
63 | SPI.begin();
64 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
65 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
66 |
67 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
68 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
69 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
70 |
71 | /* Initialize MCP2515 */
72 | mcp2515.begin();
73 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
74 | mcp2515.setNormalMode();
75 |
76 | Serial.println("setup finished");
77 | }
78 |
79 | void loop()
80 | {
81 | /* Process all pending OpenCyphal actions.
82 | */
83 | {
84 | CriticalSection crit_sec;
85 | node_hdl.spinSome();
86 | }
87 | }
88 |
89 | /**************************************************************************************
90 | * FUNCTION DEFINITION
91 | **************************************************************************************/
92 |
93 | void onReceiveBufferFull(CanardFrame const & frame)
94 | {
95 | node_hdl.onCanFrameReceived(frame);
96 | }
97 |
98 | void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg)
99 | {
100 | char msg_buf[64];
101 | snprintf(msg_buf, sizeof(msg_buf),
102 | "Uptime = %d, Health = %d, Mode = %d, VSSC = %d",
103 | msg.uptime, msg.health.value, msg.mode.value, msg.vendor_specific_status_code);
104 |
105 | Serial.println(msg_buf);
106 | }
107 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Service-Client-With-Metadata/OpenCyphal-Service-Client-With-Metadata.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example shows how to use the OpenCyphal library to request the performance of a
3 | * service from a service server.
4 | */
5 |
6 | /**************************************************************************************
7 | * INCLUDE
8 | **************************************************************************************/
9 |
10 | #include
11 |
12 | #include <107-Arduino-Cyphal.h>
13 | #include <107-Arduino-MCP2515.h>
14 | #include <107-Arduino-CriticalSection.h>
15 |
16 | /**************************************************************************************
17 | * NAMESPACE
18 | **************************************************************************************/
19 |
20 | using namespace uavcan::node;
21 |
22 | /**************************************************************************************
23 | * CONSTANTS
24 | **************************************************************************************/
25 |
26 | static int const MKRCAN_MCP2515_CS_PIN = 3;
27 | static int const MKRCAN_MCP2515_INT_PIN = 7;
28 |
29 | /**************************************************************************************
30 | * FUNCTION DECLARATION
31 | **************************************************************************************/
32 |
33 | void onReceiveBufferFull(CanardFrame const &);
34 | void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp, cyphal::TransferMetadata const & metadata);
35 |
36 | /**************************************************************************************
37 | * GLOBAL VARIABLES
38 | **************************************************************************************/
39 |
40 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
41 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
42 | [](uint8_t const data) { return SPI.transfer(data); },
43 | micros,
44 | onReceiveBufferFull,
45 | nullptr);
46 |
47 | cyphal::Node::Heap node_heap;
48 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, 28);
49 |
50 | cyphal::ServiceClient srv_client = node_hdl.create_service_client(
51 | 2*1000*1000UL,
52 | onExecuteCommand_1_1_Response_Received);
53 |
54 | /**************************************************************************************
55 | * SETUP/LOOP
56 | **************************************************************************************/
57 |
58 | void setup()
59 | {
60 | Serial.begin(9600);
61 | while(!Serial) { }
62 | delay(1000);
63 | Serial.println("|---- OpenCyphal Service Client With Metadata Example ----|");
64 |
65 | /* Setup SPI access */
66 | SPI.begin();
67 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
68 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
69 |
70 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
71 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
72 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
73 |
74 | /* Initialize MCP2515 */
75 | mcp2515.begin();
76 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
77 | mcp2515.setNormalMode();
78 |
79 | Serial.println("setup finished");
80 | }
81 |
82 | void loop()
83 | {
84 | /* Process all pending OpenCyphal actions.
85 | */
86 | {
87 | CriticalSection crit_sec;
88 | node_hdl.spinSome();
89 | }
90 |
91 | /* Publish the request once/second */
92 | static unsigned long prev = 0;
93 | unsigned long const now = millis();
94 | if(now - prev > 1000)
95 | {
96 | prev = now;
97 |
98 | /* Request some coffee. */
99 | Serial.println("Requesting some coffee");
100 | std::string const cmd_param("I want a double espresso with cream!");
101 | ExecuteCommand::Request_1_1 req;
102 | req.command = 0xCAFE;
103 | std::copy(cmd_param.begin(), cmd_param.end(), std::back_inserter(req.parameter));
104 |
105 |
106 | if (!srv_client->request(27 /* remote node id */, req)) {
107 | Serial.println("Coffee request failed.");
108 | }
109 | }
110 | }
111 |
112 | /**************************************************************************************
113 | * FUNCTION DEFINITION
114 | **************************************************************************************/
115 |
116 | void onReceiveBufferFull(CanardFrame const & frame)
117 | {
118 | node_hdl.onCanFrameReceived(frame);
119 | }
120 |
121 | void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp, cyphal::TransferMetadata const & metadata)
122 | {
123 | if (rsp.status == ExecuteCommand::Response_1_1::STATUS_SUCCESS)
124 | Serial.printf("Coffee successfully retrieved from node %i", metadata.remote_node_id);
125 | else
126 | Serial.println("I should've suspected trouble when the coffee failed to arrive.");
127 | }
128 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Service-Client/OpenCyphal-Service-Client.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example shows how to use the OpenCyphal library to request the performance of a
3 | * service from a service server.
4 | */
5 |
6 | /**************************************************************************************
7 | * INCLUDE
8 | **************************************************************************************/
9 |
10 | #include
11 |
12 | #include <107-Arduino-Cyphal.h>
13 | #include <107-Arduino-MCP2515.h>
14 | #include <107-Arduino-CriticalSection.h>
15 |
16 | /**************************************************************************************
17 | * NAMESPACE
18 | **************************************************************************************/
19 |
20 | using namespace uavcan::node;
21 |
22 | /**************************************************************************************
23 | * CONSTANTS
24 | **************************************************************************************/
25 |
26 | static int const MKRCAN_MCP2515_CS_PIN = 3;
27 | static int const MKRCAN_MCP2515_INT_PIN = 7;
28 |
29 | /**************************************************************************************
30 | * FUNCTION DECLARATION
31 | **************************************************************************************/
32 |
33 | void onReceiveBufferFull(CanardFrame const &);
34 | void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp);
35 |
36 | /**************************************************************************************
37 | * GLOBAL VARIABLES
38 | **************************************************************************************/
39 |
40 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
41 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
42 | [](uint8_t const data) { return SPI.transfer(data); },
43 | micros,
44 | onReceiveBufferFull,
45 | nullptr);
46 |
47 | cyphal::Node::Heap node_heap;
48 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, 28);
49 |
50 | cyphal::ServiceClient srv_client = node_hdl.create_service_client(
51 | 2*1000*1000UL,
52 | onExecuteCommand_1_1_Response_Received);
53 |
54 | /**************************************************************************************
55 | * SETUP/LOOP
56 | **************************************************************************************/
57 |
58 | void setup()
59 | {
60 | Serial.begin(9600);
61 | while(!Serial) { }
62 | delay(1000);
63 | Serial.println("|---- OpenCyphal Service Client Example ----|");
64 |
65 | /* Setup SPI access */
66 | SPI.begin();
67 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
68 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
69 |
70 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
71 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
72 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
73 |
74 | /* Initialize MCP2515 */
75 | mcp2515.begin();
76 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
77 | mcp2515.setNormalMode();
78 |
79 | Serial.println("setup finished");
80 | }
81 |
82 | void loop()
83 | {
84 | /* Process all pending OpenCyphal actions.
85 | */
86 | {
87 | CriticalSection crit_sec;
88 | node_hdl.spinSome();
89 | }
90 |
91 | /* Publish the request once/second */
92 | static unsigned long prev = 0;
93 | unsigned long const now = millis();
94 | if(now - prev > 1000)
95 | {
96 | prev = now;
97 |
98 | /* Request some coffee. */
99 | Serial.println("Requesting some coffee");
100 | std::string const cmd_param("I want a double espresso with cream!");
101 | ExecuteCommand::Request_1_1 req;
102 | req.command = 0xCAFE;
103 | std::copy(cmd_param.begin(), cmd_param.end(), std::back_inserter(req.parameter));
104 |
105 |
106 | if (!srv_client->request(27 /* remote node id */, req)) {
107 | Serial.println("Coffee request failed.");
108 | }
109 | }
110 | }
111 |
112 | /**************************************************************************************
113 | * FUNCTION DEFINITION
114 | **************************************************************************************/
115 |
116 | void onReceiveBufferFull(CanardFrame const & frame)
117 | {
118 | node_hdl.onCanFrameReceived(frame);
119 | }
120 |
121 | void onExecuteCommand_1_1_Response_Received(ExecuteCommand::Response_1_1 const & rsp)
122 | {
123 | if (rsp.status == ExecuteCommand::Response_1_1::STATUS_SUCCESS)
124 | Serial.println("Coffee successfully retrieved");
125 | else
126 | Serial.println("Error when retrieving coffee");
127 | }
128 |
--------------------------------------------------------------------------------
/examples/CAN/OpenCyphal-Service-Server/OpenCyphal-Service-Server.ino:
--------------------------------------------------------------------------------
1 | /*
2 | * This example shows how to use the OpenCyphal library to set up a service server
3 | * responding to requests from service clients.
4 | */
5 |
6 | /**************************************************************************************
7 | * INCLUDE
8 | **************************************************************************************/
9 |
10 | #include
11 |
12 | #include <107-Arduino-Cyphal.h>
13 | #include <107-Arduino-MCP2515.h>
14 | #include <107-Arduino-CriticalSection.h>
15 |
16 | /**************************************************************************************
17 | * NAMESPACE
18 | **************************************************************************************/
19 |
20 | using namespace uavcan::node;
21 |
22 | /**************************************************************************************
23 | * CONSTANTS
24 | **************************************************************************************/
25 |
26 | static int const MKRCAN_MCP2515_CS_PIN = 3;
27 | static int const MKRCAN_MCP2515_INT_PIN = 7;
28 |
29 | /**************************************************************************************
30 | * FUNCTION DECLARATION
31 | **************************************************************************************/
32 |
33 | void onReceiveBufferFull(CanardFrame const &);
34 | ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(ExecuteCommand::Request_1_1 const &);
35 |
36 | /**************************************************************************************
37 | * GLOBAL VARIABLES
38 | **************************************************************************************/
39 |
40 | ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
41 | []() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
42 | [](uint8_t const data) { return SPI.transfer(data); },
43 | micros,
44 | onReceiveBufferFull,
45 | nullptr);
46 |
47 | cyphal::Node::Heap node_heap;
48 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, 27);
49 |
50 | cyphal::ServiceServer execute_command_srv = node_hdl.create_service_server(
51 | 2*1000*1000UL,
52 | onExecuteCommand_1_1_Request_Received);
53 |
54 | /**************************************************************************************
55 | * SETUP/LOOP
56 | **************************************************************************************/
57 |
58 | void setup()
59 | {
60 | Serial.begin(9600);
61 | while(!Serial) { }
62 | delay(1000);
63 | Serial.println("|---- OpenCyphal Service Server Example ----|");
64 |
65 | /* Setup SPI access */
66 | SPI.begin();
67 |
68 | pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
69 | digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
70 |
71 | /* Attach interrupt handler to register MCP2515 signaled by taking INT low */
72 | pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
73 | attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
74 |
75 | /* Initialize MCP2515 */
76 | mcp2515.begin();
77 | mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
78 | mcp2515.setNormalMode();
79 |
80 | Serial.println("setup finished");
81 | }
82 |
83 | void loop()
84 | {
85 | /* Process all pending OpenCyphal actions.
86 | */
87 | {
88 | CriticalSection crit_sec;
89 | node_hdl.spinSome();
90 | }
91 | }
92 |
93 | /**************************************************************************************
94 | * FUNCTION DEFINITION
95 | **************************************************************************************/
96 |
97 | void onReceiveBufferFull(CanardFrame const & frame)
98 | {
99 | node_hdl.onCanFrameReceived(frame);
100 | }
101 |
102 | ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(ExecuteCommand::Request_1_1 const & req)
103 | {
104 | ExecuteCommand::Response_1_1 rsp;
105 | Serial.println("Coffee has been requested");
106 |
107 | std::string parameter;
108 |
109 | std::copy(
110 | req.parameter.begin(),
111 | req.parameter.end(),
112 | std::back_inserter(parameter));
113 |
114 | for (uint8_t i = 0; i < parameter.size(); i++) {
115 | Serial.print(parameter[i]);
116 | }
117 | Serial.println("");
118 |
119 | if (req.command == 0xCAFE)
120 | rsp.status = ExecuteCommand::Response_1_1::STATUS_SUCCESS;
121 | else
122 | rsp.status = ExecuteCommand::Response_1_1::STATUS_NOT_AUTHORIZED;
123 |
124 | return rsp;
125 | }
126 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/.gitignore:
--------------------------------------------------------------------------------
1 | reg/
2 | uavcan/
3 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | ##########################################################################
2 | cmake_minimum_required(VERSION 3.15)
3 | ##########################################################################
4 | set(EXAMPLE_01_TARGET host-example-01-basic-cyphal-node)
5 | ##########################################################################
6 | add_executable(${EXAMPLE_01_TARGET}
7 | host-example-01-opencyphal-basic-node.cpp
8 | socketcan.c
9 | kv_host.cpp
10 | )
11 | ##########################################################################
12 | target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17)
13 | target_link_libraries(${EXAMPLE_01_TARGET} cyphal++ pthread)
14 | ##########################################################################
15 | execute_process(
16 | COMMAND git rev-parse --short=16 HEAD
17 | WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}
18 | OUTPUT_VARIABLE GIT_HASH
19 | OUTPUT_STRIP_TRAILING_WHITESPACE
20 | )
21 | target_compile_definitions(${PROJECT_NAME} PUBLIC CYPHAL_NODE_INFO_GIT_VERSION=0x${GIT_HASH})
22 | ##########################################################################
23 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/README.md:
--------------------------------------------------------------------------------
1 |
2 | :floppy_disk: `example-01-opencyphal-basic-node`
3 | ================================================
4 | * Setup a virtual CAN interface (`vcan0`)
5 | ```bash
6 | sudo ./setup_vcan.sh
7 | ```
8 | You can observe the frames on the virtual CAN bus using `candump`
9 | ```bash
10 | candump vcan0
11 | ```
12 | * Install `yakut`
13 | ```bash
14 | python3 -m pip install yakut
15 | ```
16 | * Compile OpenCyphal DSDL
17 | ```bash
18 | yakut compile https://github.com/OpenCyphal/public_regulated_data_types/archive/refs/heads/master.zip
19 | ```
20 | * Setup `yakut`
21 | ```bash
22 | . setup_yakut.sh
23 | ```
24 | * Start `yakut`
25 | ```bash
26 | yakut monitor
27 | ```
28 | * Use `yakut`
29 |
30 | Read the register list of the node.
31 | ```bash
32 | yakut rl 42
33 | [cyphal.node.description, cyphal.node.id, cyphal.pub.temperature.id, cyphal.pub.temperature.type]
34 | ```
35 |
36 | Read/write register access:
37 | ```bash
38 | $ y r 42 cyphal.node.description
39 | basic-cyphal-node
40 |
41 | $ y r 42 cyphal.node.id
42 | 42
43 |
44 | $ y r 42 cyphal.node.id 12
45 | 12
46 |
47 | $ y r 42 cyphal.pub.counter.id
48 | 65535
49 |
50 | $ y r 42 cyphal.pub.counter.id 1001
51 | 1001
52 | ```
53 |
54 | Store changed configuration and restart node:
55 | ```bash
56 | $ y cmd 42 store
57 | $ y cmd 42 restart
58 | ```
59 | **Note**: `restart` is implemented in this example as `exit(0)`, hence you need to restart the application yourself.
60 |
61 | Subscribe to counter subject:
62 | ```bash
63 | y sub 1001:uavcan.primitive.scalar.Integer8.1.0 --with-metadata
64 | ---
65 | 1001:
66 | _meta_: {ts_system: 1691741133.026175, ts_monotonic: 25484.463219, source_node_id: 12, transfer_id: 1, priority: nominal, dtype: uavcan.primitive.scalar.Integer8.1.0}
67 | value: 1
68 | ---
69 | 1001:
70 | _meta_: {ts_system: 1691741138.027977, ts_monotonic: 25489.465034, source_node_id: 12, transfer_id: 2, priority: nominal, dtype: uavcan.primitive.scalar.Integer8.1.0}
71 | value: 2
72 | ...
73 | ```
74 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/host-example-01-opencyphal-basic-node.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDES
10 | **************************************************************************************/
11 |
12 | #include
13 | #include /* close */
14 |
15 | #include
16 | #include
17 | #include
18 | #include
19 | #include
20 |
21 | #include
22 |
23 | #include "kv_host.h"
24 | #include "socketcan.h"
25 |
26 | /**************************************************************************************
27 | * CONSTANT
28 | **************************************************************************************/
29 |
30 | static uint16_t const COUNTER_UPDATE_PERIOD_ms = 5*1000UL;
31 | static uint16_t const HEARTBEAT_UPDATE_PERIOD_ms = 1000UL;
32 |
33 | /**************************************************************************************
34 | * TYPEDEF
35 | **************************************************************************************/
36 |
37 | typedef uavcan::primitive::scalar::Integer8_1_0 CounterMsg;
38 |
39 | /**************************************************************************************
40 | * FUNCTION DECLARATION
41 | **************************************************************************************/
42 |
43 | extern "C" CanardMicrosecond micros();
44 | extern "C" unsigned long millis();
45 | uavcan::node::ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(uavcan::node::ExecuteCommand::Request_1_1 const &);
46 |
47 | /**************************************************************************************
48 | * GLOBAL VARIABLES
49 | **************************************************************************************/
50 |
51 | static cyphal::support::platform::storage::host::KeyValueStorage kv_storage;
52 | static std::shared_ptr node_registry;
53 |
54 | /**************************************************************************************
55 | * MAIN
56 | **************************************************************************************/
57 |
58 | int main(int argc, char ** argv)
59 | {
60 | int const socket_can_fd = socketcanOpen("vcan0", false);
61 | if (socket_can_fd < 0) {
62 | std::cerr << "Error opening CAN interface 'vcan0'" << std::endl;
63 | return EXIT_FAILURE;
64 | }
65 |
66 | cyphal::Node::Heap node_heap;
67 | cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [socket_can_fd] (CanardFrame const & frame) { return (socketcanPush(socket_can_fd, &frame, 1000*1000UL) > 0); });
68 | std::mutex node_mtx;
69 |
70 | cyphal::Publisher heartbeat_pub = node_hdl.create_publisher(1*1000*1000UL /* = 1 sec in usecs. */);
71 |
72 | cyphal::Publisher counter_pub;
73 |
74 | /* REGISTER ***************************************************************************/
75 |
76 | CanardNodeID node_id = node_hdl.getNodeId();
77 | CanardPortID counter_port_id = std::numeric_limits::max();
78 |
79 | node_registry = node_hdl.create_registry();
80 |
81 | const auto reg_ro_node_description = node_registry->route ("cyphal.node.description", {true}, []() { return "basic-cyphal-node"; });
82 | const auto reg_ro_pub_counter_type = node_registry->route ("cyphal.pub.counter.type", {true}, []() { return "uavcan.primitive.scalar.Integer8.1.0"; });
83 | const auto reg_rw_node_id = node_registry->expose("cyphal.node.id", {true}, node_id);
84 | const auto reg_rw_pub_counter_id = node_registry->expose("cyphal.pub.counter.id", {true}, counter_port_id);
85 |
86 | /* Configure service server for storing persistent
87 | * states upon command request.
88 | */
89 | auto const rc_load = cyphal::support::load(kv_storage, *node_registry);
90 | if (rc_load.has_value()) {
91 | std::cerr << "cyphal::support::load failed with " << static_cast(rc_load.value()) << std::endl;
92 | return EXIT_FAILURE;
93 | }
94 |
95 | cyphal::ServiceServer execute_command_srv = node_hdl.create_service_server<
96 | uavcan::node::ExecuteCommand::Request_1_1,
97 | uavcan::node::ExecuteCommand::Response_1_1>(
98 | 2*1000*1000UL,
99 | onExecuteCommand_1_1_Request_Received);
100 |
101 | /* Update node configuration from register value.
102 | */
103 | node_hdl.setNodeId(node_id);
104 | if (counter_port_id != std::numeric_limits::max())
105 | counter_pub = node_hdl.create_publisher(counter_port_id, 1*1000*1000UL /* = 1 sec in usecs. */);
106 |
107 | std::cout << "Node #" << static_cast(node_id) << std::endl
108 | << "\tCounter Port ID: " << counter_port_id << std::endl;
109 |
110 | /* NODE INFO **************************************************************************/
111 | const auto node_info = node_hdl.create_node_info
112 | (
113 | /* uavcan.node.Version.1.0 protocol_version */
114 | 1, 0,
115 | /* uavcan.node.Version.1.0 hardware_version */
116 | 1, 0,
117 | /* uavcan.node.Version.1.0 software_version */
118 | 0, 1,
119 | /* saturated uint64 software_vcs_revision_id */
120 | #ifdef CYPHAL_NODE_INFO_GIT_VERSION
121 | CYPHAL_NODE_INFO_GIT_VERSION,
122 | #else
123 | 0,
124 | #endif
125 | /* saturated uint8[16] unique_id */
126 | std::array{0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0A, 0x0B, 0x0C, 0x0D, 0x0E, 0x0F},
127 | /* saturated uint8[<=50] name */
128 | "107-systems.basic-cyphal-node"
129 | );
130 |
131 | std::atomic rx_thread_active{false};
132 | std::thread rx_thread(
133 | [&rx_thread_active, &node_hdl, &node_mtx, socket_can_fd]()
134 | {
135 | rx_thread_active = true;
136 | while (rx_thread_active)
137 | {
138 | CanardFrame rx_frame;
139 | uint8_t payload_buffer[CANARD_MTU_CAN_CLASSIC] = {0};
140 |
141 | int16_t const rc = socketcanPop(socket_can_fd, &rx_frame, sizeof(payload_buffer), payload_buffer, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, nullptr);
142 | if (rc < 0)
143 | std::cerr << "socketcanPop failed with error " << strerror(abs(rc)) << std::endl;
144 | else if (rc > 0) {
145 | std::lock_guard lock(node_mtx);
146 | node_hdl.onCanFrameReceived(rx_frame);
147 | }
148 |
149 | std::this_thread::yield();
150 | }
151 | });
152 |
153 | /* MAIN LOOP **************************************************************************/
154 |
155 | auto prev_heartbeat = millis();
156 | auto prev_counter = millis();
157 |
158 | CounterMsg counter_msg;
159 | counter_msg.value = 0;
160 |
161 | for (;;)
162 | {
163 | {
164 | std::lock_guard lock(node_mtx);
165 | node_hdl.spinSome();
166 | }
167 |
168 | auto const now = millis();
169 |
170 | if ((now - prev_heartbeat) > HEARTBEAT_UPDATE_PERIOD_ms)
171 | {
172 | prev_heartbeat = now;
173 |
174 | uavcan::node::Heartbeat_1_0 msg;
175 |
176 | msg.uptime = now / 1000;
177 | msg.health.value = uavcan::node::Health_1_0::NOMINAL;
178 | msg.mode.value = uavcan::node::Mode_1_0::OPERATIONAL;
179 | msg.vendor_specific_status_code = 0;
180 |
181 | heartbeat_pub->publish(msg);
182 | }
183 |
184 | if ((now - prev_counter) > COUNTER_UPDATE_PERIOD_ms)
185 | {
186 | prev_counter = now;
187 |
188 | if (counter_pub)
189 | counter_pub->publish(counter_msg);
190 |
191 | counter_msg.value++;
192 | }
193 |
194 | std::this_thread::yield();
195 | }
196 |
197 | rx_thread_active = false;
198 | rx_thread.join();
199 |
200 | close(socket_can_fd);
201 |
202 | return EXIT_SUCCESS;
203 | }
204 |
205 | /**************************************************************************************
206 | * FUNCTION DEFINITION
207 | **************************************************************************************/
208 |
209 | CanardMicrosecond micros()
210 | {
211 | ::timespec ts{};
212 | if (0 != clock_gettime(CLOCK_PROCESS_CPUTIME_ID, &ts))
213 | {
214 | std::cerr << "CLOCK_PROCESS_CPUTIME_ID" << std::endl;
215 | std::abort();
216 | }
217 | auto const nsec = (ts.tv_sec * 1000*1000*1000UL) + ts.tv_nsec;
218 | return static_cast(nsec / 1000UL);
219 | }
220 |
221 | unsigned long millis()
222 | {
223 | return micros() / 1000;
224 | }
225 |
226 | uavcan::node::ExecuteCommand::Response_1_1 onExecuteCommand_1_1_Request_Received(uavcan::node::ExecuteCommand::Request_1_1 const & req)
227 | {
228 | uavcan::node::ExecuteCommand::Response_1_1 rsp;
229 |
230 | if (req.command == uavcan::node::ExecuteCommand::Request_1_1::COMMAND_RESTART)
231 | {
232 | rsp.status = uavcan::node::ExecuteCommand::Response_1_1::STATUS_SUCCESS;
233 | exit(0);
234 | }
235 | else if (req.command == uavcan::node::ExecuteCommand::Request_1_1::COMMAND_STORE_PERSISTENT_STATES)
236 | {
237 | auto const rc_save = cyphal::support::save(kv_storage, *node_registry, []() { /* watchdog function */ });
238 | if (rc_save.has_value())
239 | {
240 | std::cerr << "cyphal::support::save failed with " << static_cast(rc_save.value()) << std::endl;
241 | rsp.status = uavcan::node::ExecuteCommand::Response_1_1::STATUS_FAILURE;
242 | return rsp;
243 | }
244 | rsp.status = uavcan::node::ExecuteCommand::Response_1_1::STATUS_SUCCESS;
245 | }
246 | else {
247 | rsp.status = uavcan::node::ExecuteCommand::Response_1_1::STATUS_BAD_COMMAND;
248 | }
249 |
250 | return rsp;
251 | }
252 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal-Support/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE
10 | **************************************************************************************/
11 |
12 | #include "kv_host.h"
13 |
14 | #if !defined(__GNUC__) || (__GNUC__ >= 11)
15 |
16 | #include
17 |
18 | #include
19 | #include
20 |
21 | /**************************************************************************************
22 | * NAMESPACE
23 | **************************************************************************************/
24 |
25 | namespace cyphal::support::platform::storage::host
26 | {
27 |
28 | /**************************************************************************************
29 | * PRIVATE FREE FUNCTIONS
30 | **************************************************************************************/
31 |
32 | [[nodiscard]] static inline std::string toFilename(std::string_view const key)
33 | {
34 | auto const key_hash = std::hash{}(key);
35 | std::stringstream key_filename;
36 | key_filename << key_hash;
37 | return key_filename.str();
38 | }
39 |
40 | /**************************************************************************************
41 | * PUBLIC MEMBER FUNCTIONS
42 | **************************************************************************************/
43 |
44 | auto KeyValueStorage::get(const std::string_view key, const std::size_t size, void* const data) const
45 | -> std::variant
46 | {
47 | std::ifstream in(toFilename(key), std::ifstream::in | std::ifstream::binary);
48 |
49 | if (!in.good())
50 | return Error::Existence;
51 |
52 | in.read(static_cast(data), size);
53 | size_t const bytes_read = in ? size : in.gcount();
54 | in.close();
55 |
56 | return bytes_read;
57 | }
58 |
59 | auto KeyValueStorage::put(const std::string_view key, const std::size_t size, const void* const data)
60 | -> std::optional
61 | {
62 | std::ofstream out(toFilename(key), std::ofstream::in | std::ofstream::binary | std::ofstream::trunc);
63 |
64 | if (!out.good())
65 | return Error::Existence;
66 |
67 | out.write(static_cast(data), size);
68 | out.close();
69 |
70 | return std::nullopt;
71 | }
72 |
73 | auto KeyValueStorage::drop(const std::string_view key) -> std::optional
74 | {
75 | if (std::remove(toFilename(key).c_str()))
76 | return Error::IO;
77 |
78 | return std::nullopt;
79 | }
80 |
81 | /**************************************************************************************
82 | * NAMESPACE
83 | **************************************************************************************/
84 |
85 | } /* cyphal::support::platform::storage::host */
86 |
87 | #endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */
88 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/kv_host.h:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal-Support/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include <107-Arduino-Cyphal.h>
15 |
16 | #if !defined(__GNUC__) || (__GNUC__ >= 11)
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal::support::platform::storage::host
23 | {
24 |
25 | /**************************************************************************************
26 | * CLASS DECLARATION
27 | **************************************************************************************/
28 |
29 | class KeyValueStorage final : public interface::KeyValueStorage
30 | {
31 | public:
32 | KeyValueStorage() { }
33 | virtual ~KeyValueStorage() { }
34 |
35 | /// The return value is the number of bytes read into the buffer or the error.
36 | [[nodiscard]] virtual auto get(const std::string_view key, const std::size_t size, void* const data) const
37 | -> std::variant override;
38 |
39 | /// Existing data, if any, is replaced entirely. New file and its parent directories created implicitly.
40 | /// Either all or none of the data bytes are written.
41 | [[nodiscard]] virtual auto put(const std::string_view key, const std::size_t size, const void* const data)
42 | -> std::optional override;
43 |
44 | /// Remove key. If the key does not exist, the existence error is returned.
45 | [[nodiscard]] virtual auto drop(const std::string_view key) -> std::optional override;
46 | };
47 |
48 | /**************************************************************************************
49 | * NAMESPACE
50 | **************************************************************************************/
51 |
52 | } /* cyphal::support::platform::storage::host */
53 |
54 | #endif /* !defined(__GNUC__) || (__GNUC__ >= 11) */
55 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/setup_vcan.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | # Make sure the script runs with super user privileges.
3 | [ "$UID" -eq 0 ] || exec sudo bash "$0" "$@"
4 | # Load the kernel module.
5 | modprobe vcan
6 | # Create the virtual CAN interface.
7 | ip link add dev vcan0 type vcan
8 | # Bring the virtual CAN interface online.
9 | ip link set up vcan0
10 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/setup_yakut.sh:
--------------------------------------------------------------------------------
1 | export YAKUT_COMPILE_OUTPUT=.yakut
2 | export YAKUT_PATH="$YAKUT_COMPILE_OUTPUT"
3 | export UAVCAN__CAN__IFACE='socketcan:vcan0'
4 | export UAVCAN__CAN__MTU=8
5 | export UAVCAN__NODE__ID=$(yakut accommodate) # Pick an unoccupied node-ID automatically for this shell session.
6 | echo "Auto-selected node-ID for this session: $UAVCAN__NODE__ID"
7 |
--------------------------------------------------------------------------------
/examples/CAN/host-example-01-opencyphal-basic-node/socketcan.h:
--------------------------------------------------------------------------------
1 | /// __ __ _______ __ __ _______ _______ __ __
2 | /// | | | | / _ ` | | | | / ____| / _ ` | ` | |
3 | /// | | | | | |_| | | | | | | | | |_| | | `| |
4 | /// | |_| | | _ | ` `_/ / | |____ | _ | | |` |
5 | /// `_______/ |__| |__| `_____/ `_______| |__| |__| |__| `__|
6 | /// | | | | | |
7 | /// ----o------o------------o---------o------o---------o-------
8 | ///
9 | /// This is a basic adapter library that bridges Libcanard with SocketCAN.
10 | /// Read the API documentation for usage information.
11 | ///
12 | /// To integrate the library into your application, just copy-paste the c/h files into your project tree.
13 | ///
14 | /// --------------------------------------------------------------------------------------------------------------------
15 | /// Changelog
16 | ///
17 | /// v2.0 - Added loop-back functionality.
18 | /// API change in socketcanPop(): loopback flag added.
19 | /// - Changed to kernel-based time-stamping for received frames for improved accuracy.
20 | /// API change in socketcanPop(): time stamp clock source is now CLOCK_REALTIME, vs CLOCK_TAI before.
21 | ///
22 | /// v1.0 - Initial release
23 | /// --------------------------------------------------------------------------------------------------------------------
24 | ///
25 | /// This software is distributed under the terms of the MIT License.
26 | /// Copyright (c) 2020 UAVCAN Development Team.
27 | /// Author: Pavel Kirienko
28 |
29 | #ifndef SOCKETCAN_H_INCLUDED
30 | #define SOCKETCAN_H_INCLUDED
31 |
32 | #include
33 | #include
34 | #include
35 | #include
36 |
37 | #ifdef __cplusplus
38 | extern "C" {
39 | #endif
40 |
41 | /// File descriptor alias.
42 | typedef int SocketCANFD;
43 |
44 | /// Initialize a new non-blocking (sic!) SocketCAN socket and return its handle on success.
45 | /// On failure, a negated errno is returned.
46 | /// To discard the socket just call close() on it; no additional de-initialization activities are required.
47 | /// The argument can_fd enables support for CAN FD frames.
48 | SocketCANFD socketcanOpen(const char* const iface_name, const bool can_fd);
49 |
50 | /// Enqueue a new extended CAN data frame for transmission.
51 | /// Block until the frame is enqueued or until the timeout is expired.
52 | /// Zero timeout makes the operation non-blocking.
53 | /// Returns 1 on success, 0 on timeout, negated errno on error.
54 | int16_t socketcanPush(const SocketCANFD fd, const CanardFrame* const frame, const CanardMicrosecond timeout_usec);
55 |
56 | /// Fetch a new extended CAN data frame from the RX queue.
57 | /// If the received frame is not an extended-ID data frame, it will be dropped and the function will return early.
58 | /// The payload pointer of the returned frame will point to the payload_buffer. It can be a stack-allocated array.
59 | /// The payload_buffer_size shall be large enough (64 bytes is enough for CAN FD), otherwise an error is returned.
60 | /// The received frame timestamp will be set to CLOCK_REALTIME by the kernel, sampled near the moment of its arrival.
61 | /// The loopback flag pointer is used to both indicate and control behavior when a looped-back message is received.
62 | /// If the flag pointer is NULL, loopback frames are silently dropped; if not NULL, they are accepted and indicated
63 | /// using this flag.
64 | /// The function will block until a frame is received or until the timeout is expired. It may return early.
65 | /// Zero timeout makes the operation non-blocking.
66 | /// Returns 1 on success, 0 on timeout, negated errno on error.
67 | int16_t socketcanPop(const SocketCANFD fd,
68 | CanardFrame* const out_frame,
69 | const size_t payload_buffer_size,
70 | void* const payload_buffer,
71 | const CanardMicrosecond timeout_usec,
72 | bool* const loopback);
73 |
74 | /// The configuration of a single extended 29-bit data frame acceptance filter.
75 | /// Bits above the 29-th shall be cleared.
76 | typedef struct SocketCANFilterConfig
77 | {
78 | uint32_t extended_id;
79 | uint32_t mask;
80 | } SocketCANFilterConfig;
81 |
82 | /// Apply the specified acceptance filter configuration.
83 | /// Note that it is only possible to accept extended-format data frames.
84 | /// The default configuration is to accept everything.
85 | /// Returns 0 on success, negated errno on error.
86 | int16_t socketcanFilter(const SocketCANFD fd, const size_t num_configs, const SocketCANFilterConfig* const configs);
87 |
88 | #ifdef __cplusplus
89 | }
90 | #endif
91 |
92 | #endif
93 |
--------------------------------------------------------------------------------
/extras/codespell-ignore-words-list.txt:
--------------------------------------------------------------------------------
1 | arithmetics
2 | wan
3 |
--------------------------------------------------------------------------------
/extras/script/Dockerfile:
--------------------------------------------------------------------------------
1 | FROM ubuntu:latest
2 |
3 | # set a directory for the app
4 | WORKDIR /usr/src/app
5 |
6 | # install dependencies
7 | RUN apt-get update -y
8 | RUN apt-get install -y apt-utils
9 | RUN apt-get install -y locales
10 | RUN apt-get install -yq tzdata
11 | RUN echo "Europe/Berlin" > /etc/timezone && \
12 | touch /etc/locale.gen && \
13 | dpkg-reconfigure -f noninteractive tzdata && \
14 | sed -i -e 's/# en_US.UTF-8 UTF-8/en_US.UTF-8 UTF-8/' /etc/locale.gen && \
15 | sed -i -e 's/# de_DE.UTF-8 UTF-8/de_DE.UTF-8 UTF-8/' /etc/locale.gen && \
16 | echo 'LANG="de_DE.UTF-8"'>/etc/default/locale && \
17 | dpkg-reconfigure --frontend=noninteractive locales && \
18 | update-locale LANG=de_DE.UTF-8
19 |
20 | ENV LANG de_DE.UTF-8
21 | ENV LANGUAGE de_DE.UTF-8
22 | ENV LC_ALL de_DE.UTF-8
23 |
24 | RUN apt-get install -y bash
25 | RUN apt-get install -y git
26 | RUN apt-get install -y python3-pip
27 | RUN pip3 install -U nunavut
28 |
29 | CMD ["/bin/bash", "-c", "cd /107-Arduino-Cyphal; ./extras/script/update_cpp_header.sh; exit"]
30 |
--------------------------------------------------------------------------------
/extras/script/README.md:
--------------------------------------------------------------------------------
1 |
2 | ### How-to generate C++ headers with [nunavut](https://github.com/OpenCyphal/nunavut)
3 | Install Docker via `snap` or follow the official [instructions](https://docs.docker.com/engine/install/ubuntu/):
4 | ```bash
5 | sudo snap install docker
6 | ```
7 | **Note**: You may need to add your user to the `docker` group:
8 | ```bash
9 | sudo usermod -a -G docker $USER
10 | ```
11 | Generating the C++ header files using a Docker container:
12 | ```bash
13 | cd extras/script
14 | ./build_docker.sh
15 | ./docker_codegen.sh
16 | ```
17 |
--------------------------------------------------------------------------------
/extras/script/build_docker.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | docker build --pull --no-cache -t 107_arduino_cyphal_headergen .
3 |
--------------------------------------------------------------------------------
/extras/script/docker_codegen.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 |
3 | docker run -it -v ${PWD}/../../:/107-Arduino-Cyphal 107_arduino_cyphal_headergen
4 |
--------------------------------------------------------------------------------
/extras/script/update_cpp_header.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 |
3 | SCRIPT_DIR=$(dirname $(readlink -f "$0"))
4 | SRC_DIR="$SCRIPT_DIR/../../src"
5 | HEADER_DIR="$SCRIPT_DIR/../../src/types"
6 | NUNAVUT_DIR="$SCRIPT_DIR/../../src/nunavut"
7 |
8 | cd /tmp
9 | rm -rf public_regulated_data_types
10 | git clone https://github.com/OpenCyphal/public_regulated_data_types
11 |
12 | rm -rf zubax_dsdl
13 | git clone https://github.com/Zubax/zubax_dsdl
14 |
15 | echo "nnvg version: "
16 | nnvg --version
17 | echo ""
18 |
19 | echo "Generating code..."
20 | nnvg --experimental-languages \
21 | --language-standard=c++17 \
22 | --target-language cpp \
23 | --pp-max-emptylines=1 \
24 | --pp-trim-trailing-whitespace \
25 | --target-endianness=any \
26 | --outdir public_regulated_data_types/uavcan-header \
27 | public_regulated_data_types/uavcan
28 | nnvg --experimental-languages \
29 | --language-standard=c++17 \
30 | --target-language cpp \
31 | --pp-max-emptylines=1 \
32 | --pp-trim-trailing-whitespace \
33 | --target-endianness=any \
34 | --lookup public_regulated_data_types/uavcan \
35 | --outdir public_regulated_data_types/reg-header \
36 | public_regulated_data_types/reg
37 | nnvg --experimental-languages \
38 | --language-standard=c++17 \
39 | --target-language cpp \
40 | --pp-max-emptylines=1 \
41 | --pp-trim-trailing-whitespace \
42 | --target-endianness=any \
43 | --lookup public_regulated_data_types/uavcan \
44 | --outdir zubax_dsdl/zubax/zubax-header \
45 | zubax_dsdl/zubax
46 |
47 | echo "Copying code to destination"
48 | cp -R public_regulated_data_types/uavcan-header/nunavut/* "$NUNAVUT_DIR"
49 | cp -R public_regulated_data_types/uavcan-header/uavcan "$HEADER_DIR"
50 | cp -R public_regulated_data_types/reg-header/reg "$HEADER_DIR"
51 | cp -R zubax_dsdl/zubax/zubax-header/zubax "$HEADER_DIR"
52 |
53 | echo "Fixing include paths"
54 | cd $HEADER_DIR
55 | find . -type f -exec sed -i 's/"reg\///g' {} +
60 |
61 | echo "Fixing definition of NUNAVUT_ASSERT"
62 | cd $NUNAVUT_DIR/support
63 | sed -i -- 's/#define NUNAVUT_SUPPORT_SERIALIZATION_HPP_INCLUDED/#define NUNAVUT_SUPPORT_SERIALIZATION_HPP_INCLUDED\n\n#include \n\n#define NUNAVUT_ASSERT(expr) assert(expr)\n/g' serialization.hpp
64 |
65 |
66 | echo "Auto-generate DSDL_Types.h.impl which contains a list of all generated files"
67 | cd $SRC_DIR
68 | touch DSDL_Types.h.impl
69 | truncate -s 0 DSDL_Types.h.impl
70 | for i in $(find ./types -type f -name "*.hpp" -printf "%P\n")
71 | do
72 | printf "#include \"types/%s\" \n" $i >> DSDL_Types.h.impl
73 | done
74 |
--------------------------------------------------------------------------------
/extras/test/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | ##########################################################################
2 | cmake_minimum_required(VERSION 3.15)
3 | ##########################################################################
4 | project("test_cyphal++")
5 | ##########################################################################
6 | if(CMAKE_C_COMPILER_ID STREQUAL "GNU" AND CMAKE_C_COMPILER_VERSION VERSION_LESS 11)
7 | message(WARNING "GNU C compiler version ${CMAKE_C_COMPILER_VERSION} is too old and is unsupported. Version 11+ is required.")
8 | endif()
9 | if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 11)
10 | message(WARNING "GNU C++ compiler version ${CMAKE_CXX_COMPILER_VERSION} is too old and is unsupported. Version 11+ is required.")
11 | endif()
12 | ##########################################################################
13 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
14 | ##########################################################################
15 | include_directories(external/catch2/v2.13.10/include)
16 | include_directories(../../src)
17 | include_directories(../../src/util/registry)
18 | ##########################################################################
19 | add_executable(${PROJECT_NAME}
20 | src/test_main.cpp
21 | src/test_registry_impl.cpp
22 | src/test_registry_value.cpp
23 | )
24 | ##########################################################################
25 | target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic -Werror --coverage)
26 | ##########################################################################
27 | target_link_libraries(${PROJECT_NAME} PRIVATE gcov)
28 | ##########################################################################
29 | target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_17)
30 | ##########################################################################
31 |
--------------------------------------------------------------------------------
/extras/test/src/test_main.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE/MAIN
10 | **************************************************************************************/
11 |
12 | #define CATCH_CONFIG_MAIN
13 | #include
14 |
--------------------------------------------------------------------------------
/extras/test/src/test_registry_impl.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Pavel Kirienko
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #include
9 | #include
10 |
11 | namespace cyphal::registry
12 | {
13 |
14 | TEST_CASE("Basic")
15 | {
16 | Registry reg;
17 |
18 | // Ensure empty.
19 | REQUIRE(0 == reg.size());
20 | REQUIRE(reg.index(0).name.size() == 0);
21 | REQUIRE_FALSE(reg.get("foo"));
22 | REQUIRE(SetError::Existence == reg.set("foo", Value()).value());
23 |
24 | // Create exposable values. Using exposure because its functionality is a superset of the routing functionality.
25 | std::array val_arr{{123, 456, -789}};
26 | auto r_arr = reg.expose("arr", Registry::Options{true}, val_arr); // Mutable.
27 | REQUIRE(r_arr);
28 | REQUIRE(1 == reg.size());
29 | REQUIRE(0 == std::strncmp("arr", reinterpret_cast(reg.index(0).name.data()), 3));
30 | {
31 | std::array vec{{1.0F, 2.0F, 3.0F, 4.0F, 5.0F, 6.0F}};
32 | // Create registers.
33 | const auto r_pi = reg.route("pi", {true}, [] { return 3.14F; }); // RO
34 | const auto r_mat = reg.expose("vec", {}, vec); // RW
35 | REQUIRE(3 == reg.size());
36 |
37 | // Constant registers cannot be changed.
38 | REQUIRE(SetError::Mutability == reg.set("pi", makeValue(123.456F)).value());
39 | {
40 | const auto r_pi_get = reg.get("pi");
41 | REQUIRE(r_pi_get);
42 | REQUIRE(Approx(3.14F) == get(r_pi_get.value().value).value());
43 | REQUIRE(r_pi_get.value().flags.persistent);
44 | REQUIRE(!r_pi_get.value().flags.mutable_);
45 | }
46 |
47 | // Mutate mutable array.
48 | {
49 | const auto set_result = reg.set("arr", makeValue(-654.456F)); // Coerced to -654.
50 | REQUIRE_FALSE(set_result);
51 | const auto r_arr_get = reg.get("arr");
52 | REQUIRE(r_arr_get);
53 | const auto val = get>(r_arr_get.value().value).value();
54 | REQUIRE(-654 == val[0]);
55 | REQUIRE(456 == val[1]);
56 | REQUIRE(-789 == val[2]);
57 | REQUIRE(0 == val[3]);
58 | REQUIRE(r_arr_get.value().flags.persistent);
59 | REQUIRE(r_arr_get.value().flags.mutable_);
60 | }
61 | // Ensure the array itself is actually updated.
62 | REQUIRE(-654 == val_arr[0]);
63 | REQUIRE(456 == val_arr[1]);
64 | REQUIRE(-789 == val_arr[2]);
65 |
66 | // Mutate the matrix.
67 | {
68 | const auto set_result = reg.set("vec", makeValue(std::array{10, -2, 30}));
69 | REQUIRE_FALSE(set_result);
70 | const auto r_mat_get = reg.get("vec");
71 | REQUIRE(r_mat_get);
72 | const auto val = get>(r_mat_get.value().value).value();
73 | REQUIRE(10 == val[0]); // From the vector.
74 | REQUIRE(-2 == val[1]); // From the vector.
75 | REQUIRE(30 == val[2]); // From the vector.
76 | REQUIRE(4 == val[3]); // Original retained.
77 | REQUIRE(5 == val[4]); // Original retained.
78 | REQUIRE(6 == val[5]); // Original retained.
79 | REQUIRE(!r_mat_get.value().flags.persistent);
80 | REQUIRE(r_mat_get.value().flags.mutable_);
81 | }
82 | // Ensure the matrix itself is actually updated.
83 | REQUIRE(Approx(10) == vec[0]);
84 | REQUIRE(Approx(-2) == vec[1]);
85 | REQUIRE(Approx(30) == vec[2]);
86 | REQUIRE(Approx(4) == vec[3]);
87 | REQUIRE(Approx(5) == vec[4]);
88 | REQUIRE(Approx(6) == vec[5]);
89 |
90 | // Attempt incoercible mutation.
91 | REQUIRE(SetError::Coercion == reg.set("vec", makeValue("this is not a number")).value());
92 |
93 | // No such register.
94 | REQUIRE(SetError::Existence == reg.set("mat", makeValue("this is not a number")).value());
95 |
96 | // Semantics error.
97 | const auto r_semantics = reg.route(
98 | "sem", //
99 | {},
100 | [] { return makeValue("anything"); },
101 | [](const Value&) { return false; });
102 | REQUIRE(SetError::Semantics == reg.set("sem", makeValue("whatever")).value());
103 |
104 | // List for diagnostics.
105 | for (auto i = 0U; true; i++)
106 | {
107 | const auto name = reg.index(i);
108 | if (0 == name.name.size())
109 | {
110 | break;
111 | }
112 | }
113 | }
114 |
115 | // The other registers are removed, but the first one remains.
116 | REQUIRE(1 == reg.size());
117 | REQUIRE(0 == std::strncmp("arr", reinterpret_cast(reg.index(0).name.data()), 3));
118 |
119 | // Drop the first one as well.
120 | r_arr.reset();
121 | REQUIRE(0 == reg.size());
122 | }
123 |
124 | } // namespace cyphal::registry
125 |
--------------------------------------------------------------------------------
/keywords.txt:
--------------------------------------------------------------------------------
1 | #######################################
2 | # Syntax Coloring Map for 107-Arduino-Cyphal
3 | #######################################
4 |
5 | #######################################
6 | # Class (KEYWORD1)
7 | #######################################
8 |
9 | Node KEYWORD1
10 | Heap KEYWORD1
11 | Publisher KEYWORD1
12 | Subscription KEYWORD1
13 | ServiceServer KEYWORD1
14 | ServiceClient KEYWORD1
15 | Request KEYWORD1
16 | Response KEYWORD1
17 |
18 | #######################################
19 | # Methods and Functions (KEYWORD2)
20 | #######################################
21 |
22 | setNodeId KEYWORD2
23 | getNodeId KEYWORD2
24 | create_publisher KEYWORD2
25 | create_subscription KEYWORD2
26 | create_service_server KEYWORD2
27 | create_service_client KEYWORD2
28 | spinSome KEYWORD2
29 | onCanFrameReceived KEYWORD2
30 | publish KEYWORD2
31 | request KEYWORD2
32 |
33 | #######################################
34 | # Constants (LITERAL1)
35 | #######################################
36 |
37 | DEFAULT_O1HEAP_SIZE LITERAL1
38 | DEFAULT_NODE_ID LITERAL1
39 | DEFAULT_RX_QUEUE_SIZE LITERAL1
40 | DEFAULT_TX_QUEUE_SIZE LITERAL1
41 | DEFAULT_MTU_SIZE LITERAL1
42 |
--------------------------------------------------------------------------------
/library.properties:
--------------------------------------------------------------------------------
1 | name=107-Arduino-Cyphal
2 | version=3.5.0
3 | author=Alexander Entinger
4 | maintainer=Alexander Entinger
5 | sentence=Arduino library for providing a convenient C++ interface for accessing OpenCyphal.
6 | paragraph=
7 | category=Communication
8 | url=https://github.com/107-systems/107-Arduino-Cyphal
9 | architectures=rp2040,renesas_portenta,renesas_uno
10 | includes=107-Arduino-Cyphal.h
11 | depends=
12 |
--------------------------------------------------------------------------------
/src/107-Arduino-Cyphal.h:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include "Node.hpp"
15 | #include "DSDL_Types.h"
16 | #include "Publisher.hpp"
17 | #include "Subscription.hpp"
18 | #include "ServiceClient.hpp"
19 | #include "ServiceServer.hpp"
20 | #include "util/storage/register_storage.hpp"
21 |
--------------------------------------------------------------------------------
/src/CanRxQueueItem.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include
15 |
16 | #include "libcanard/canard.h"
17 |
18 | #include
19 |
20 | /**************************************************************************************
21 | * NAMESPACE
22 | **************************************************************************************/
23 |
24 | namespace cyphal
25 | {
26 |
27 | /**************************************************************************************
28 | * CLASS DECLARATION
29 | **************************************************************************************/
30 |
31 | template
32 | class CanRxQueueItem
33 | {
34 | static_assert((MTU_BYTES == CANARD_MTU_CAN_CLASSIC) || (MTU_BYTES == CANARD_MTU_CAN_FD),
35 | "CanRxQueueItem can only have an MTU size of either 8 (CANARD_MTU_CAN_CLASSIC) or 64 (CANARD_MTU_CAN_FD).");
36 | public:
37 | CanRxQueueItem()
38 | : _extended_can_id{0}, _payload_size{0}, _payload_buf{}, _rx_timestamp_usec{0}
39 | {}
40 |
41 | CanRxQueueItem(CanardFrame const *const frame, CanardMicrosecond const rx_timestamp_usec)
42 | : _extended_can_id{frame->extended_can_id}, _payload_size{frame->payload_size},
43 | _payload_buf{fromCanardFrame(frame)}, _rx_timestamp_usec{rx_timestamp_usec}
44 | {}
45 |
46 |
47 | [[nodiscard]] uint32_t extended_can_id() const
48 | { return _extended_can_id; }
49 |
50 | [[nodiscard]] size_t payload_size() const
51 | { return _payload_size; }
52 |
53 | [[nodiscard]] std::array const &payload_buf() const
54 | { return _payload_buf; }
55 |
56 | [[nodiscard]] CanardMicrosecond rx_timestamp_usec() const
57 | { return _rx_timestamp_usec; }
58 |
59 |
60 | private:
61 | uint32_t _extended_can_id;
62 | size_t _payload_size;
63 | std::array _payload_buf;
64 | CanardMicrosecond _rx_timestamp_usec;
65 |
66 | static std::array fromCanardFrame(CanardFrame const *const frame)
67 | {
68 | std::array payload_buf{};
69 | std::copy(static_cast(frame->payload),
70 | static_cast(frame->payload) + std::min(frame->payload_size, MTU_BYTES),
71 | payload_buf.begin());
72 | return payload_buf;
73 | }
74 | };
75 |
76 | /**************************************************************************************
77 | * NAMESPACE
78 | **************************************************************************************/
79 |
80 | } /* cyphal */
81 |
--------------------------------------------------------------------------------
/src/CircularBuffer.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include
15 |
16 | #include
17 | #include
18 |
19 | /**************************************************************************************
20 | * NAMESPACE
21 | **************************************************************************************/
22 |
23 | namespace cyphal
24 | {
25 |
26 | /**************************************************************************************
27 | * CLASS DECLARATION
28 | **************************************************************************************/
29 |
30 | class CircularBufferBase
31 | {
32 | public:
33 | CircularBufferBase() { }
34 | virtual ~CircularBufferBase() { }
35 | CircularBufferBase(CircularBufferBase const &) = delete;
36 | CircularBufferBase(CircularBufferBase &&) = delete;
37 | CircularBufferBase &operator=(CircularBufferBase const &) = delete;
38 | CircularBufferBase &operator=(CircularBufferBase &&) = delete;
39 | };
40 |
41 | template
42 | class CircularBuffer : public CircularBufferBase
43 | {
44 | public:
45 | CircularBuffer(size_t const heap_size);
46 | virtual ~CircularBuffer();
47 |
48 |
49 | void enqueue(T const & val);
50 | T * peek();
51 | void pop();
52 |
53 |
54 |
55 | private:
56 | std::unique_ptr _buffer;
57 | size_t _size, _head, _tail, _num_elems;
58 |
59 | bool isFull() const { return (_num_elems == _size); }
60 | bool isEmpty() const { return (_num_elems == 0); }
61 | size_t nextIndex(size_t const index) { return ((index + 1) % _size); }
62 | };
63 |
64 | /**************************************************************************************
65 | * NAMESPACE
66 | **************************************************************************************/
67 |
68 | } /* cyphal */
69 |
70 | /**************************************************************************************
71 | * TEMPLATE IMPLEMENTATION
72 | **************************************************************************************/
73 |
74 | #include "CircularBuffer.ipp"
75 |
--------------------------------------------------------------------------------
/src/CircularBuffer.ipp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * NAMESPACE
10 | **************************************************************************************/
11 |
12 | namespace cyphal
13 | {
14 |
15 | /**************************************************************************************
16 | * CTOR/DTOR
17 | **************************************************************************************/
18 |
19 | template
20 | CircularBuffer::CircularBuffer(size_t const heap_size)
21 | : _buffer{new T[heap_size]}
22 | , _size{heap_size}
23 | , _head{0}
24 | , _tail{0}
25 | , _num_elems{0}
26 | {
27 |
28 | }
29 |
30 | template
31 | CircularBuffer::~CircularBuffer()
32 | {
33 | _size = 0;
34 | _head = 0;
35 | _tail = 0;
36 | _num_elems = 0;
37 | }
38 |
39 | /**************************************************************************************
40 | * PUBLIC MEMBER FUNCTIONS
41 | **************************************************************************************/
42 |
43 | template
44 | void CircularBuffer::enqueue(T const & val)
45 | {
46 | if (isFull()) return;
47 |
48 | _buffer.get()[_head] = val;
49 | _head = nextIndex(_head);
50 | _num_elems++;
51 | }
52 |
53 | template
54 | T * CircularBuffer::peek()
55 | {
56 | if (isEmpty()) return nullptr;
57 |
58 | T * val_ptr = &(_buffer.get()[_tail]);
59 | return val_ptr;
60 | }
61 |
62 | template
63 | void CircularBuffer::pop()
64 | {
65 | if (isEmpty()) return;
66 |
67 | _tail = nextIndex(_tail);
68 | _num_elems--;
69 | }
70 |
71 | /**************************************************************************************
72 | * NAMESPACE
73 | **************************************************************************************/
74 |
75 | } /* cyphal */
76 |
--------------------------------------------------------------------------------
/src/DSDL_Types.h:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #pragma GCC diagnostic push
15 | #pragma GCC diagnostic ignored "-Wtype-limits"
16 | #pragma GCC diagnostic ignored "-Wattributes"
17 | #pragma GCC diagnostic ignored "-Wunused-parameter"
18 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
19 | #include "DSDL_Types.h.impl"
20 | #pragma GCC diagnostic pop
21 |
--------------------------------------------------------------------------------
/src/Node.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE
10 | **************************************************************************************/
11 |
12 | #include "Node.hpp"
13 |
14 | #include
15 |
16 | #include "util/nodeinfo/NodeInfo.hpp"
17 | #include "util/registry/Registry.hpp"
18 | #include "util/port/PortListPublisher.hpp"
19 |
20 | /**************************************************************************************
21 | * NAMESPACE
22 | **************************************************************************************/
23 |
24 | namespace cyphal
25 | {
26 |
27 | /**************************************************************************************
28 | * CTOR/DTOR
29 | **************************************************************************************/
30 |
31 | Node::Node(uint8_t * heap_ptr,
32 | size_t const heap_size,
33 | MicrosFunc const micros_func,
34 | CanFrameTxFunc const tx_func,
35 | CanardNodeID const node_id,
36 | size_t const tx_queue_capacity,
37 | size_t const rx_queue_capacity,
38 | size_t const mtu_bytes)
39 | : _o1heap_ins{o1heapInit(heap_ptr, heap_size)}
40 | , _canard_hdl{canardInit(Node::o1heap_allocate, Node::o1heap_free)}
41 | , _micros_func{micros_func}
42 | , _tx_func{tx_func}
43 | , _canard_tx_queue{canardTxInit(tx_queue_capacity, mtu_bytes)}
44 | , _canard_rx_queue{(mtu_bytes == CANARD_MTU_CAN_CLASSIC) ? static_cast(new CircularBufferCan(rx_queue_capacity)) : static_cast(new CircularBufferCanFd(rx_queue_capacity))}
45 | , _mtu_bytes{mtu_bytes}
46 | , _opt_port_list_pub{std::nullopt}
47 | {
48 | _canard_hdl.node_id = node_id;
49 | _canard_hdl.user_reference = static_cast(_o1heap_ins);
50 |
51 | _opt_port_list_pub = std::make_shared(*this, _micros_func);
52 | }
53 |
54 | /**************************************************************************************
55 | * PUBLIC MEMBER FUNCTIONS
56 | **************************************************************************************/
57 |
58 | #if !defined(__GNUC__) || (__GNUC__ >= 11)
59 | Registry Node::create_registry()
60 | {
61 | return std::make_shared(*this, _micros_func);
62 | }
63 | #endif
64 |
65 | NodeInfo Node::create_node_info(uint8_t const protocol_major, uint8_t const protocol_minor,
66 | uint8_t const hardware_major, uint8_t const hardware_minor,
67 | uint8_t const software_major, uint8_t const software_minor,
68 | uint64_t const software_vcs_revision_id,
69 | std::array const & unique_id,
70 | std::string const & name)
71 | {
72 | return std::make_shared(*this,
73 | protocol_major, protocol_minor,
74 | hardware_major, hardware_minor,
75 | software_major, software_minor,
76 | software_vcs_revision_id,
77 | unique_id,
78 | name);
79 | }
80 |
81 | NodeInfo Node::create_node_info(uint8_t const protocol_major, uint8_t const protocol_minor,
82 | uint8_t const hardware_major, uint8_t const hardware_minor,
83 | uint8_t const software_major, uint8_t const software_minor,
84 | uint64_t const software_vcs_revision_id,
85 | std::array const & unique_id,
86 | std::string const & name,
87 | uint64_t const image_crc)
88 | {
89 | return std::make_shared(*this,
90 | protocol_major, protocol_minor,
91 | hardware_major, hardware_minor,
92 | software_major, software_minor,
93 | software_vcs_revision_id,
94 | unique_id,
95 | name, image_crc);
96 | }
97 |
98 | void Node::spinSome()
99 | {
100 | processPortList();
101 | processRxQueue();
102 | processTxQueue();
103 | }
104 |
105 | void Node::processPortList()
106 | {
107 | if (_opt_port_list_pub.has_value())
108 | _opt_port_list_pub.value()->update();
109 | }
110 |
111 |
112 | void Node::onCanFrameReceived(CanardFrame const & frame)
113 | {
114 | if (_mtu_bytes == CANARD_MTU_CAN_CLASSIC)
115 | {
116 | CanRxQueueItem const rx_queue_item(&frame, _micros_func());
117 | static_cast(_canard_rx_queue.get())->enqueue(rx_queue_item);
118 | }
119 | else if (_mtu_bytes == CANARD_MTU_CAN_FD)
120 | {
121 | CanRxQueueItem const rx_queue_item(&frame, _micros_func());
122 | static_cast(_canard_rx_queue.get())->enqueue(rx_queue_item);
123 | }
124 | }
125 |
126 | bool Node::enqueue_transfer(CanardMicrosecond const tx_timeout_usec,
127 | CanardTransferMetadata const * const transfer_metadata,
128 | size_t const payload_buf_size,
129 | uint8_t const * const payload_buf)
130 | {
131 | int32_t const rc = canardTxPush(&_canard_tx_queue,
132 | &_canard_hdl,
133 | _micros_func() + tx_timeout_usec,
134 | transfer_metadata,
135 | payload_buf_size,
136 | payload_buf);
137 |
138 | bool const success = (rc >= 0);
139 | return success;
140 | }
141 |
142 | void Node::unsubscribe(CanardPortID const port_id, CanardTransferKind const transfer_kind)
143 | {
144 | canardRxUnsubscribe(&_canard_hdl,
145 | transfer_kind,
146 | port_id);
147 | }
148 |
149 | /**************************************************************************************
150 | * PRIVATE MEMBER FUNCTIONS
151 | **************************************************************************************/
152 |
153 | void * Node::o1heap_allocate(CanardInstance * const ins, size_t const amount)
154 | {
155 | O1HeapInstance * o1heap = reinterpret_cast(ins->user_reference);
156 | return o1heapAllocate(o1heap, amount);
157 | }
158 |
159 | void Node::o1heap_free(CanardInstance * const ins, void * const pointer)
160 | {
161 | O1HeapInstance * o1heap = reinterpret_cast(ins->user_reference);
162 | o1heapFree(o1heap, pointer);
163 | }
164 |
165 | void Node::processRxQueue()
166 | {
167 | if (_mtu_bytes == CANARD_MTU_CAN_CLASSIC)
168 | {
169 | CircularBufferCan * can_rx_queue_ptr = static_cast(_canard_rx_queue.get());
170 | CanRxQueueItem const * rx_queue_item = can_rx_queue_ptr->peek();
171 | if (!rx_queue_item) return;
172 | processRxFrame(rx_queue_item);
173 | can_rx_queue_ptr->pop();
174 | }
175 | else if (_mtu_bytes == CANARD_MTU_CAN_FD)
176 | {
177 | CircularBufferCanFd * canfd_rx_queue_ptr = static_cast(_canard_rx_queue.get());
178 | CanRxQueueItem const * rx_queue_item = canfd_rx_queue_ptr->peek();
179 | if (!rx_queue_item) return;
180 | processRxFrame(rx_queue_item);
181 | canfd_rx_queue_ptr->pop();
182 | }
183 | }
184 |
185 | void Node::processTxQueue()
186 | {
187 | for(CanardTxQueueItem * tx_queue_item = const_cast(canardTxPeek(&_canard_tx_queue));
188 | tx_queue_item != nullptr;
189 | tx_queue_item = const_cast(canardTxPeek(&_canard_tx_queue)))
190 | {
191 | /* Discard the frame if the transmit deadline has expired. */
192 | if (_micros_func() > tx_queue_item->tx_deadline_usec) {
193 | _canard_hdl.memory_free(&_canard_hdl, canardTxPop(&_canard_tx_queue, tx_queue_item));
194 | continue;
195 | }
196 |
197 | /* Attempt to transmit the frame via CAN. */
198 | if (_tx_func(tx_queue_item->frame)) {
199 | _canard_hdl.memory_free(&_canard_hdl, canardTxPop(&_canard_tx_queue, tx_queue_item));
200 | continue;
201 | }
202 |
203 | return;
204 | }
205 | }
206 |
207 | /**************************************************************************************
208 | * NAMESPACE
209 | **************************************************************************************/
210 |
211 | } /* cyphal */
212 |
--------------------------------------------------------------------------------
/src/Node.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include
15 |
16 | #undef max
17 | #undef min
18 | #include
19 | #include
20 | #include
21 | #include
22 |
23 | #include "PublisherBase.hpp"
24 | #include "SubscriptionBase.h"
25 | #include "CircularBuffer.hpp"
26 | #include "ServiceClientBase.hpp"
27 | #include "ServiceServerBase.hpp"
28 | #include "CanRxQueueItem.hpp"
29 | #include "util/nodeinfo/NodeInfoBase.hpp"
30 | #include "util/registry/registry_impl.hpp"
31 | #include "util/port/PortListPublisherBase.hpp"
32 |
33 | #include "libo1heap/o1heap.h"
34 | #include "libcanard/canard.h"
35 |
36 | /**************************************************************************************
37 | * NAMESPACE
38 | **************************************************************************************/
39 |
40 | namespace cyphal
41 | {
42 |
43 | /**************************************************************************************
44 | * CLASS DECLARATION
45 | **************************************************************************************/
46 |
47 | class Node
48 | {
49 | public:
50 |
51 | typedef std::function MicrosFunc;
52 | typedef std::function CanFrameTxFunc;
53 |
54 | template
55 | struct alignas(O1HEAP_ALIGNMENT) Heap final : public std::array {};
56 |
57 |
58 | static size_t constexpr DEFAULT_O1HEAP_SIZE = 16384UL;
59 | static CanardNodeID constexpr DEFAULT_NODE_ID = 42;
60 | static size_t constexpr DEFAULT_RX_QUEUE_SIZE = 64;
61 | static size_t constexpr DEFAULT_TX_QUEUE_SIZE = 64;
62 | static size_t constexpr DEFAULT_MTU_SIZE = CANARD_MTU_CAN_CLASSIC;
63 |
64 |
65 | Node(uint8_t * heap_ptr,
66 | size_t const heap_size,
67 | MicrosFunc const micros_func,
68 | CanFrameTxFunc const tx_func,
69 | CanardNodeID const node_id,
70 | size_t const tx_queue_capacity,
71 | size_t const rx_queue_capacity,
72 | size_t const mtu_bytes);
73 |
74 | Node(uint8_t * heap_ptr, size_t const heap_size, MicrosFunc const micros_func, CanFrameTxFunc const tx_func)
75 | : Node(heap_ptr, heap_size, micros_func, tx_func, DEFAULT_NODE_ID, DEFAULT_TX_QUEUE_SIZE, DEFAULT_RX_QUEUE_SIZE, DEFAULT_MTU_SIZE) { }
76 |
77 | Node(uint8_t * heap_ptr, size_t const heap_size, MicrosFunc const micros_func, CanFrameTxFunc const tx_func, CanardNodeID const node_id)
78 | : Node(heap_ptr, heap_size, micros_func, tx_func, node_id, DEFAULT_TX_QUEUE_SIZE, DEFAULT_RX_QUEUE_SIZE, DEFAULT_MTU_SIZE) { }
79 |
80 |
81 | inline void setNodeId(CanardNodeID const node_id) { _canard_hdl.node_id = node_id; }
82 | inline CanardNodeID getNodeId() const { return _canard_hdl.node_id; }
83 |
84 |
85 | template
86 | Publisher create_publisher(CanardMicrosecond const tx_timeout_usec);
87 | template
88 | Publisher create_publisher(CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec);
89 |
90 | template
91 | Subscription create_subscription(OnReceiveCb&& on_receive_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
92 | template
93 | Subscription create_subscription(CanardPortID const port_id, OnReceiveCb&& on_receive_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
94 |
95 | template
96 | ServiceServer create_service_server(CanardMicrosecond const tx_timeout_usec, OnRequestCb&& on_request_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
97 | template
98 | ServiceServer create_service_server(CanardPortID const request_port_id, CanardMicrosecond const tx_timeout_usec, OnRequestCb&& on_request_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
99 |
100 | template
101 | ServiceClient create_service_client(CanardMicrosecond const tx_timeout_usec, OnResponseCb&& on_response_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
102 | template
103 | ServiceClient create_service_client(CanardPortID const response_port_id, CanardMicrosecond const tx_timeout_usec, OnResponseCb&& on_response_cb, CanardMicrosecond const tid_timeout_usec = CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
104 |
105 | #if !defined(__GNUC__) || (__GNUC__ >= 11)
106 | Registry create_registry();
107 | #endif
108 |
109 | NodeInfo create_node_info(uint8_t const protocol_major, uint8_t const protocol_minor,
110 | uint8_t const hardware_major, uint8_t const hardware_minor,
111 | uint8_t const software_major, uint8_t const software_minor,
112 | uint64_t const software_vcs_revision_id,
113 | std::array const & unique_id,
114 | std::string const & name);
115 |
116 | NodeInfo create_node_info(uint8_t const protocol_major, uint8_t const protocol_minor,
117 | uint8_t const hardware_major, uint8_t const hardware_minor,
118 | uint8_t const software_major, uint8_t const software_minor,
119 | uint64_t const software_vcs_revision_id,
120 | std::array const & unique_id,
121 | std::string const & name,
122 | uint64_t const image_crc);
123 |
124 | /* Must be called from the application to process
125 | * all received CAN frames.
126 | */
127 | void spinSome();
128 | /* Must be called from the application upon the
129 | * reception of a can frame.
130 | */
131 | void onCanFrameReceived(CanardFrame const & frame);
132 |
133 |
134 | bool enqueue_transfer(CanardMicrosecond const tx_timeout_usec,
135 | CanardTransferMetadata const * const transfer_metadata,
136 | size_t const payload_buf_size,
137 | uint8_t const * const payload_buf);
138 | void unsubscribe(CanardPortID const port_id, CanardTransferKind const transfer_kind);
139 |
140 |
141 | private:
142 | typedef CircularBuffer> CircularBufferCan;
143 | typedef CircularBuffer> CircularBufferCanFd;
144 |
145 | O1HeapInstance * _o1heap_ins;
146 | CanardInstance _canard_hdl;
147 | MicrosFunc const _micros_func;
148 | CanFrameTxFunc const _tx_func;
149 | CanardTxQueue _canard_tx_queue;
150 | std::shared_ptr _canard_rx_queue;
151 | size_t const _mtu_bytes;
152 |
153 | std::optional _opt_port_list_pub;
154 |
155 | static void * o1heap_allocate(CanardInstance * const ins, size_t const amount);
156 | static void o1heap_free (CanardInstance * const ins, void * const pointer);
157 |
158 | void processRxQueue();
159 | void processTxQueue();
160 | void processPortList();
161 | template
162 | void processRxFrame(CanRxQueueItem const * const rx_queue_item);
163 | };
164 |
165 | /**************************************************************************************
166 | * NAMESPACE
167 | **************************************************************************************/
168 |
169 | } /* cyphal */
170 |
171 | /**************************************************************************************
172 | * TEMPLATE SOURCE FILE
173 | **************************************************************************************/
174 |
175 | #include "Node.ipp"
176 |
--------------------------------------------------------------------------------
/src/Node.ipp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE
10 | **************************************************************************************/
11 |
12 | #include "Publisher.hpp"
13 | #include "Subscription.hpp"
14 | #include "ServiceClient.hpp"
15 | #include "ServiceServer.hpp"
16 |
17 | /**************************************************************************************
18 | * NAMESPACE
19 | **************************************************************************************/
20 |
21 | namespace cyphal
22 | {
23 |
24 | /**************************************************************************************
25 | * PUBLIC MEMBER FUNCTIONS
26 | **************************************************************************************/
27 |
28 | template
29 | Publisher Node::create_publisher(CanardMicrosecond const tx_timeout_usec)
30 | {
31 | static_assert(T::_traits_::HasFixedPortID, "T does not have a fixed port id.");
32 | return create_publisher(T::_traits_::FixedPortId, tx_timeout_usec);
33 | }
34 |
35 | template
36 | Publisher Node::create_publisher(CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec)
37 | {
38 | static_assert(!T::_traits_::IsServiceType, "T is not message type");
39 |
40 | if (_opt_port_list_pub.has_value())
41 | _opt_port_list_pub.value()->add_publisher(port_id);
42 |
43 | return std::make_shared>(
44 | *this,
45 | port_id,
46 | tx_timeout_usec
47 | );
48 | }
49 |
50 | template
51 | Subscription Node::create_subscription(OnReceiveCb&& on_receive_cb, CanardMicrosecond const tid_timeout_usec)
52 | {
53 | static_assert(T::_traits_::HasFixedPortID, "T does not have a fixed port id.");
54 | return create_subscription(T::_traits_::FixedPortId, on_receive_cb, tid_timeout_usec);
55 | }
56 |
57 | template
58 | Subscription Node::create_subscription(CanardPortID const port_id, OnReceiveCb&& on_receive_cb, CanardMicrosecond const tid_timeout_usec)
59 | {
60 | static_assert(!T::_traits_::IsServiceType, "T is not message type");
61 |
62 | if (_opt_port_list_pub.has_value())
63 | _opt_port_list_pub.value()->add_subscriber(port_id);
64 |
65 | auto sub = std::make_shared>(
66 | *this,
67 | port_id,
68 | std::forward(on_receive_cb)
69 | );
70 |
71 | int8_t const rc = canardRxSubscribe(&_canard_hdl,
72 | CanardTransferKindMessage,
73 | port_id,
74 | T::_traits_::ExtentBytes,
75 | tid_timeout_usec,
76 | &(sub->canard_rx_subscription()));
77 | if (rc < 0)
78 | return nullptr;
79 |
80 | return sub;
81 | }
82 |
83 | template
84 | ServiceServer Node::create_service_server(CanardMicrosecond const tx_timeout_usec, OnRequestCb&& on_request_cb, CanardMicrosecond const tid_timeout_usec)
85 | {
86 | static_assert(T_REQ::_traits_::HasFixedPortID, "T_REQ does not have a fixed port id.");
87 | static_assert(T_RSP::_traits_::HasFixedPortID, "T_RSP does not have a fixed port id.");
88 |
89 | return create_service_server(T_REQ::_traits_::FixedPortId, tx_timeout_usec, on_request_cb, tid_timeout_usec);
90 | }
91 |
92 | template
93 | ServiceServer Node::create_service_server(CanardPortID const request_port_id, CanardMicrosecond const tx_timeout_usec, OnRequestCb&& on_request_cb, CanardMicrosecond const tid_timeout_usec)
94 | {
95 | static_assert(T_REQ::_traits_::IsRequest, "T_REQ is not a request");
96 | static_assert(T_RSP::_traits_::IsResponse, "T_RSP is not a response");
97 |
98 | if (_opt_port_list_pub.has_value())
99 | _opt_port_list_pub.value()->add_service_server(request_port_id);
100 |
101 | auto srv = std::make_shared>(
102 | *this,
103 | request_port_id,
104 | tx_timeout_usec,
105 | std::forward(on_request_cb)
106 | );
107 |
108 | int8_t const rc = canardRxSubscribe(&_canard_hdl,
109 | CanardTransferKindRequest,
110 | request_port_id,
111 | T_REQ::_traits_::ExtentBytes,
112 | tid_timeout_usec,
113 | &(srv->canard_rx_subscription()));
114 | if (rc < 0)
115 | return nullptr;
116 |
117 | return srv;
118 | }
119 |
120 | template
121 | ServiceClient Node::create_service_client(CanardMicrosecond const tx_timeout_usec, OnResponseCb&& on_response_cb, CanardMicrosecond const tid_timeout_usec)
122 | {
123 | static_assert(T_REQ::_traits_::HasFixedPortID, "T_REQ does not have a fixed port id.");
124 | static_assert(T_RSP::_traits_::HasFixedPortID, "T_RSP does not have a fixed port id.");
125 |
126 | return create_service_client(T_RSP::_traits_::FixedPortId, tx_timeout_usec, on_response_cb, tid_timeout_usec);
127 | }
128 |
129 | template
130 | ServiceClient Node::create_service_client(CanardPortID const response_port_id, CanardMicrosecond const tx_timeout_usec, OnResponseCb&& on_response_cb, CanardMicrosecond const tid_timeout_usec)
131 | {
132 | static_assert(T_REQ::_traits_::IsRequest, "T_REQ is not a request");
133 | static_assert(T_RSP::_traits_::IsResponse, "T_RSP is not a response");
134 |
135 | if (_opt_port_list_pub.has_value())
136 | _opt_port_list_pub.value()->add_service_client(response_port_id);
137 |
138 | auto clt = std::make_shared>(
139 | *this,
140 | response_port_id,
141 | tx_timeout_usec,
142 | std::forward(on_response_cb)
143 | );
144 |
145 | int8_t const rc = canardRxSubscribe(&_canard_hdl,
146 | CanardTransferKindResponse,
147 | response_port_id,
148 | T_RSP::_traits_::ExtentBytes,
149 | tid_timeout_usec,
150 | &(clt->canard_rx_subscription()));
151 | if (rc < 0)
152 | return nullptr;
153 |
154 | return clt;
155 | }
156 |
157 | template
158 | void Node::processRxFrame(CanRxQueueItem const * const rx_queue_item)
159 | {
160 | CanardFrame rx_frame;
161 | rx_frame.extended_can_id = rx_queue_item->extended_can_id();
162 | rx_frame.payload_size = rx_queue_item->payload_size();
163 | rx_frame.payload = reinterpret_cast(rx_queue_item->payload_buf().data());
164 |
165 | CanardRxTransfer rx_transfer;
166 | CanardRxSubscription * rx_subscription;
167 | int8_t const result = canardRxAccept(&_canard_hdl,
168 | rx_queue_item->rx_timestamp_usec(),
169 | &rx_frame,
170 | 0, /* redundant_transport_index */
171 | &rx_transfer,
172 | &rx_subscription);
173 |
174 | if(result == 1)
175 | {
176 | /* Obtain the pointer to the subscribed object and in invoke its reception callback. */
177 | impl::SubscriptionBase * sub_ptr = static_cast(rx_subscription->user_reference);
178 | sub_ptr->onTransferReceived(rx_transfer);
179 |
180 | /* Free dynamically allocated memory after processing. */
181 | _canard_hdl.memory_free(&_canard_hdl, rx_transfer.payload);
182 | }
183 | }
184 |
185 | /**************************************************************************************
186 | * NAMESPACE
187 | **************************************************************************************/
188 |
189 | } /* cyphal */
190 |
--------------------------------------------------------------------------------
/src/Publisher.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include "PublisherBase.hpp"
15 |
16 | #include "Node.hpp"
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal
23 | {
24 |
25 | namespace impl
26 | {
27 |
28 | /**************************************************************************************
29 | * CLASS DECLARATION
30 | **************************************************************************************/
31 |
32 | template
33 | class Publisher final : public PublisherBase
34 | {
35 | public:
36 | Publisher(Node & node_hdl, CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec)
37 | : _node_hdl{node_hdl}
38 | , _port_id{port_id}
39 | , _tx_timeout_usec{tx_timeout_usec}
40 | , _transfer_id{0}
41 | { }
42 | virtual ~Publisher() { }
43 |
44 | bool publish(T const & msg) override;
45 |
46 | private:
47 | Node & _node_hdl;
48 | CanardPortID const _port_id;
49 | CanardMicrosecond const _tx_timeout_usec;
50 | CanardTransferID _transfer_id;
51 | };
52 |
53 | /**************************************************************************************
54 | * NAMESPACE
55 | **************************************************************************************/
56 |
57 | } /* impl */
58 | } /* cyphal */
59 |
60 | /**************************************************************************************
61 | * TEMPLATE IMPLEMENTATION
62 | **************************************************************************************/
63 |
64 | #include "Publisher.ipp"
65 |
--------------------------------------------------------------------------------
/src/Publisher.ipp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE
10 | **************************************************************************************/
11 |
12 | #include
13 |
14 | #undef max
15 | #undef min
16 | #include
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal
23 | {
24 |
25 | namespace impl
26 | {
27 |
28 | /**************************************************************************************
29 | * PUBLIC MEMBER FUNCTIONS
30 | **************************************************************************************/
31 |
32 | template
33 | bool Publisher::publish(T const & msg)
34 | {
35 | #pragma GCC diagnostic push
36 | #pragma GCC diagnostic ignored "-Wpedantic"
37 | CanardTransferMetadata const transfer_metadata =
38 | {
39 | .priority = CanardPriorityNominal,
40 | .transfer_kind = CanardTransferKindMessage,
41 | .port_id = _port_id,
42 | .remote_node_id = CANARD_NODE_ID_UNSET,
43 | .transfer_id = _transfer_id++,
44 | };
45 | #pragma GCC diagnostic pop
46 |
47 | /* Serialize message into payload buffer. */
48 | std::array msg_buf;
49 | nunavut::support::bitspan msg_buf_bitspan{msg_buf};
50 | auto const rc = serialize(msg, msg_buf_bitspan);
51 | if (!rc) return false;
52 |
53 | /* Serialize transfer into a series of CAN frames */
54 | return _node_hdl.enqueue_transfer(_tx_timeout_usec,
55 | &transfer_metadata,
56 | *rc,
57 | msg_buf.data());
58 | }
59 |
60 | /**************************************************************************************
61 | * NAMESPACE
62 | **************************************************************************************/
63 |
64 | } /* impl */
65 | } /* cyphal */
66 |
--------------------------------------------------------------------------------
/src/PublisherBase.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include
15 |
16 | /**************************************************************************************
17 | * NAMESPACE
18 | **************************************************************************************/
19 |
20 | namespace cyphal
21 | {
22 |
23 | namespace impl
24 | {
25 |
26 | /**************************************************************************************
27 | * CLASS DECLARATION
28 | **************************************************************************************/
29 |
30 | template
31 | class PublisherBase
32 | {
33 | public:
34 | PublisherBase() { }
35 | virtual ~PublisherBase() { }
36 | PublisherBase(PublisherBase const &) = delete;
37 | PublisherBase(PublisherBase &&) = delete;
38 | PublisherBase &operator=(PublisherBase const &) = delete;
39 | PublisherBase &operator=(PublisherBase &&) = delete;
40 |
41 | virtual bool publish(T const & msg) = 0;
42 | };
43 |
44 | /**************************************************************************************
45 | * NAMESPACE
46 | **************************************************************************************/
47 |
48 | } /* impl */
49 |
50 | /**************************************************************************************
51 | * TYPEDEF
52 | **************************************************************************************/
53 |
54 | template
55 | using Publisher = std::shared_ptr>;
56 |
57 | /**************************************************************************************
58 | * NAMESPACE
59 | **************************************************************************************/
60 |
61 | } /* cyphal */
62 |
--------------------------------------------------------------------------------
/src/ServiceClient.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include "ServiceClientBase.hpp"
15 |
16 | #include "Node.hpp"
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal
23 | {
24 |
25 | namespace impl
26 | {
27 |
28 | /**************************************************************************************
29 | * CLASS DECLARATION
30 | **************************************************************************************/
31 |
32 | template
33 | class ServiceClient final : public ServiceClientBase
34 | {
35 | public:
36 | ServiceClient(Node & node_hdl, CanardPortID const response_port_id, CanardMicrosecond const tx_timeout_usec, OnResponseCb on_response_cb)
37 | : _node_hdl{node_hdl}
38 | , _response_port_id{response_port_id}
39 | , _tx_timeout_usec{tx_timeout_usec}
40 | , _on_response_cb{on_response_cb}
41 | , _transfer_id{0}
42 | { }
43 | virtual ~ServiceClient();
44 |
45 |
46 | bool request(CanardNodeID const remote_node_id, T_REQ const & req) override;
47 | bool onTransferReceived(CanardRxTransfer const & transfer) override;
48 |
49 |
50 | private:
51 | Node & _node_hdl;
52 | CanardPortID const _response_port_id;
53 | CanardMicrosecond const _tx_timeout_usec;
54 | OnResponseCb _on_response_cb;
55 | CanardTransferID _transfer_id;
56 | };
57 |
58 | /**************************************************************************************
59 | * NAMESPACE
60 | **************************************************************************************/
61 |
62 | } /* impl */
63 | } /* cyphal */
64 |
65 | /**************************************************************************************
66 | * TEMPLATE IMPLEMENTATION
67 | **************************************************************************************/
68 |
69 | #include "ServiceClient.ipp"
70 |
--------------------------------------------------------------------------------
/src/ServiceClient.ipp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE
10 | **************************************************************************************/
11 |
12 | #include
13 |
14 | #undef max
15 | #undef min
16 | #include
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal
23 | {
24 |
25 | namespace impl {
26 |
27 | /**************************************************************************************
28 | * CTOR/DTOR
29 | **************************************************************************************/
30 |
31 | template
32 | ServiceClient::~ServiceClient()
33 | {
34 | _node_hdl.unsubscribe(_response_port_id, SubscriptionBase::canard_transfer_kind());
35 | }
36 |
37 | /**************************************************************************************
38 | * PUBLIC MEMBER FUNCTIONS
39 | **************************************************************************************/
40 |
41 | template
42 | bool ServiceClient::request(CanardNodeID const remote_node_id, T_REQ const & req)
43 | {
44 | #pragma GCC diagnostic push
45 | #pragma GCC diagnostic ignored "-Wpedantic"
46 | CanardTransferMetadata const transfer_metadata =
47 | {
48 | .priority = CanardPriorityNominal,
49 | .transfer_kind = CanardTransferKindRequest,
50 | .port_id = _response_port_id,
51 | .remote_node_id = remote_node_id,
52 | .transfer_id = _transfer_id++,
53 | };
54 | #pragma GCC diagnostic pop
55 |
56 | /* Serialize message into payload buffer. */
57 | std::array req_buf;
58 | nunavut::support::bitspan req_buf_bitspan{req_buf};
59 | auto const req_rc = serialize(req, req_buf_bitspan);
60 | if (!req_rc) return false;
61 |
62 | /* Serialize transfer into a series of CAN frames. */
63 | return _node_hdl.enqueue_transfer(_tx_timeout_usec,
64 | &transfer_metadata,
65 | *req_rc,
66 | req_buf.data());
67 | }
68 |
69 | template
70 | bool ServiceClient::onTransferReceived(CanardRxTransfer const & transfer)
71 | {
72 | /* Deserialize the response message. */
73 | T_RSP rsp;
74 | nunavut::support::const_bitspan rsp_bitspan(static_cast(transfer.payload), transfer.payload_size);
75 | auto const rc = deserialize(rsp, rsp_bitspan);
76 | if (!rc) return false;
77 |
78 | /* Invoke the user registered callback. */
79 | if constexpr (std::is_invocable_v) {
80 | _on_response_cb(rsp, SubscriptionBase::fillMetadata(transfer));
81 | } else {
82 | _on_response_cb(rsp);
83 | }
84 |
85 | return true;
86 | }
87 |
88 | /**************************************************************************************
89 | * NAMESPACE
90 | **************************************************************************************/
91 |
92 | } /* impl */
93 | } /* cyphal */
94 |
--------------------------------------------------------------------------------
/src/ServiceClientBase.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include
15 |
16 | #include "SubscriptionBase.h"
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal
23 | {
24 |
25 | namespace impl
26 | {
27 |
28 | /**************************************************************************************
29 | * CLASS DECLARATION
30 | **************************************************************************************/
31 |
32 | template
33 | class ServiceClientBase : public SubscriptionBase
34 | {
35 | public:
36 | ServiceClientBase() : SubscriptionBase{CanardTransferKindResponse} { }
37 | virtual ~ServiceClientBase() { }
38 | virtual bool request(CanardNodeID const remote_node_id, T_REQ const & req) = 0;
39 | };
40 |
41 | /**************************************************************************************
42 | * NAMESPACE
43 | **************************************************************************************/
44 |
45 | } /* impl */
46 |
47 | /**************************************************************************************
48 | * TYPEDEF
49 | **************************************************************************************/
50 |
51 | template
52 | using ServiceClient = std::shared_ptr>;
53 |
54 | /**************************************************************************************
55 | * NAMESPACE
56 | **************************************************************************************/
57 |
58 | } /* cyphal */
59 |
--------------------------------------------------------------------------------
/src/ServiceServer.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | #pragma once
9 |
10 | /**************************************************************************************
11 | * INCLUDE
12 | **************************************************************************************/
13 |
14 | #include "ServiceServerBase.hpp"
15 |
16 | #include "Node.hpp"
17 |
18 | /**************************************************************************************
19 | * NAMESPACE
20 | **************************************************************************************/
21 |
22 | namespace cyphal
23 | {
24 |
25 | namespace impl
26 | {
27 |
28 | /**************************************************************************************
29 | * CLASS DECLARATION
30 | **************************************************************************************/
31 |
32 | template
33 | class ServiceServer final : public ServiceServerBase
34 | {
35 | public:
36 | ServiceServer(Node & node_hdl, CanardPortID const request_port_id, CanardMicrosecond const tx_timeout_usec, OnRequestCb on_request_cb)
37 | : _node_hdl{node_hdl}
38 | , _request_port_id{request_port_id}
39 | , _tx_timeout_usec{tx_timeout_usec}
40 | , _on_request_cb{on_request_cb}
41 | { }
42 | virtual ~ServiceServer();
43 |
44 |
45 | bool onTransferReceived(CanardRxTransfer const & transfer) override;
46 |
47 |
48 | private:
49 | Node & _node_hdl;
50 | CanardPortID const _request_port_id;
51 | CanardMicrosecond const _tx_timeout_usec;
52 | OnRequestCb _on_request_cb;
53 | };
54 |
55 | /**************************************************************************************
56 | * NAMESPACE
57 | **************************************************************************************/
58 |
59 | } /* impl */
60 | } /* cyphal */
61 |
62 | /**************************************************************************************
63 | * TEMPLATE IMPLEMENTATION
64 | **************************************************************************************/
65 |
66 | #include "ServiceServer.ipp"
67 |
--------------------------------------------------------------------------------
/src/ServiceServer.ipp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger
5 | * Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6 | */
7 |
8 | /**************************************************************************************
9 | * INCLUDE
10 | **************************************************************************************/
11 |
12 | #undef max
13 | #undef min
14 | #include
15 |
16 | /**************************************************************************************
17 | * NAMESPACE
18 | **************************************************************************************/
19 |
20 | namespace cyphal
21 | {
22 |
23 | namespace impl
24 | {
25 |
26 | /**************************************************************************************
27 | * CTOR/DTOR
28 | **************************************************************************************/
29 |
30 | template
31 | ServiceServer::~ServiceServer()
32 | {
33 | _node_hdl.unsubscribe(_request_port_id, SubscriptionBase::canard_transfer_kind());
34 | }
35 |
36 | /**************************************************************************************
37 | * PUBLIC MEMBER FUNCTIONS
38 | **************************************************************************************/
39 |
40 | template
41 | bool ServiceServer::onTransferReceived(CanardRxTransfer const & transfer)
42 | {
43 | /* Deserialize the request message. */
44 | T_REQ req;
45 | nunavut::support::const_bitspan req_buf_bitspan(static_cast(transfer.payload), transfer.payload_size);
46 | auto const req_rc = deserialize(req, req_buf_bitspan);
47 | if (!req_rc) return false;
48 |
49 | /* Invoke the service callback and obtain the desired response. */
50 | T_RSP rsp;
51 | if constexpr (std::is_invocable_v) {
52 | rsp = _on_request_cb(req, fillMetadata(transfer));
53 | } else {
54 | rsp = _on_request_cb(req);
55 | }
56 |
57 | /* Serialize the response message. */
58 | std::array rsp_buf;
59 | nunavut::support::bitspan rsp_buf_bitspan{rsp_buf};
60 | auto const rsp_rc = serialize(rsp, rsp_buf_bitspan);
61 | if (!rsp_rc) return false;
62 |
63 | #pragma GCC diagnostic push
64 | #pragma GCC diagnostic ignored "-Wpedantic"
65 | /* Enqueue the transfer. */
66 | CanardTransferMetadata const transfer_metadata =
67 | {
68 | .priority = CanardPriorityNominal,
69 | .transfer_kind = CanardTransferKindResponse,
70 | .port_id = transfer.metadata.port_id,
71 | .remote_node_id = transfer.metadata.remote_node_id,
72 | .transfer_id = transfer.metadata.transfer_id,
73 | };
74 | #pragma GCC diagnostic pop
75 |
76 | /* Serialize transfer into a series of CAN frames */
77 | return _node_hdl.enqueue_transfer(_tx_timeout_usec,
78 | &transfer_metadata,
79 | *rsp_rc,
80 | rsp_buf.data());
81 | }
82 |
83 | /**************************************************************************************
84 | * NAMESPACE
85 | **************************************************************************************/
86 |
87 | } /* impl */
88 | } /* cyphal */
89 |
--------------------------------------------------------------------------------
/src/ServiceServerBase.hpp:
--------------------------------------------------------------------------------
1 | /**
2 | * This software is distributed under the terms of the MIT License.
3 | * Copyright (c) 2020-2023 LXRobotics.
4 | * Author: Alexander Entinger