Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 19 additions & 1 deletion axiomatic_adapter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,15 @@ find_package(ament_cmake_ros REQUIRED)
find_package(Boost REQUIRED COMPONENTS system)
find_package(CLI11 REQUIRED)
find_package(socketcan_adapter REQUIRED)
find_package(Threads REQUIRED)

# Axiomatic Adapter Library
add_library(axiomatic_adapter SHARED src/axiomatic_adapter.cpp)
add_library(axiomatic_adapter SHARED
src/axiomatic_adapter.cpp
src/axiomatic_protocol.cpp
src/udp_client.cpp
src/axiomatic_fd_backend.cpp
)

target_compile_features(axiomatic_adapter PUBLIC c_std_99 cxx_std_17)
target_include_directories(axiomatic_adapter PUBLIC
Expand All @@ -57,6 +63,7 @@ target_link_libraries(axiomatic_adapter
PUBLIC socketcan_adapter::socketcan_adapter
PRIVATE
Boost::system
Threads::Threads
)

install(DIRECTORY include/ DESTINATION include)
Expand Down Expand Up @@ -113,6 +120,17 @@ if(BUILD_TESTING)
add_test(NAME test_axiomatic_adapter COMMAND test_axiomatic_adapter)
endif()
endif()

# Tests for the new FD-backend codec + transport use GoogleTest; the legacy
# tests above use Catch2. Both frameworks coexist during the transition.
find_package(ament_cmake_gtest QUIET)
if(ament_cmake_gtest_FOUND)
ament_add_gtest(test_axiomatic_protocol test/test_axiomatic_protocol.cpp)
target_link_libraries(test_axiomatic_protocol axiomatic_adapter)

ament_add_gtest(test_udp_client test/test_udp_client.cpp)
target_link_libraries(test_udp_client axiomatic_adapter)
endif()
endif()

ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
Expand Down
76 changes: 54 additions & 22 deletions axiomatic_adapter/include/axiomatic_adapter/axiomatic_adapter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,28 +25,36 @@
#include <string>

#include "socketcan_adapter/can_frame.hpp"
#include "socketcan_adapter/i_can_backend.hpp"
#include "socketcan_adapter/socketcan_adapter.hpp" // for polymath::socketcan::SocketState

namespace polymath
{
namespace can
{

/// @brief State of TCP socket, error, open or closed
enum class TCPSocketState
{
ERROR = -1,
OPEN = 0,
CLOSED = 1,
};
/// @brief State of TCP socket — kept as an alias of polymath::socketcan::SocketState
/// since the legacy enum's values matched the interface enum exactly. The alias
/// preserves source compatibility for existing callers (e.g. the bridge node
/// using `TCPSocketState::OPEN`) while letting AxiomaticAdapter implement the
/// ICanBackend::get_socket_state() contract.
using TCPSocketState = polymath::socketcan::SocketState;

/// @class polymath::can::AxiomaticAdapter
/// @brief Creates and manages a tcp connection and simplifies the interface.
/// Generally does not throw, but returns booleans to tell you success
class AxiomaticAdapter : public std::enable_shared_from_this<AxiomaticAdapter>
/// Generally does not throw, but returns booleans to tell you success.
///
/// As of 2026-05 AxiomaticAdapter implements polymath::socketcan::ICanBackend
/// so that consumers can hold a non-owning ICanBackend* and select the
/// transport (kernel SocketCAN, this Axiomatic ETH-CAN bridge) at construction
/// time. The retrofit is purely additive: the existing constructor that takes
/// receive + error callbacks remains the canonical setup path, and runtime
/// callback setters were added to satisfy the interface — set them BEFORE
/// startReceptionThread() to avoid a benign race with the rx thread.
class AxiomaticAdapter : public polymath::socketcan::ICanBackend, public std::enable_shared_from_this<AxiomaticAdapter>
{
public:
/// @brief Mapped to std lib, but should be remapped to Polymath Safety compatible versions
using socket_error_string_t = std::string;
using socket_error_string_t = polymath::socketcan::ICanBackend::socket_error_string_t;

static constexpr std::chrono::milliseconds DEFAULT_SOCKET_RECEIVE_TIMEOUT_MS{100};
static constexpr std::chrono::milliseconds JOIN_RECEPTION_TIMEOUT_MS{100};
Expand All @@ -65,20 +73,20 @@ class AxiomaticAdapter : public std::enable_shared_from_this<AxiomaticAdapter>
const std::chrono::milliseconds & receive_timeout_ms = AxiomaticAdapter::DEFAULT_SOCKET_RECEIVE_TIMEOUT_MS);

/// @brief Destructor for AxiomaticAdapter
virtual ~AxiomaticAdapter();
~AxiomaticAdapter() override;

/// @brief Open TCP Socket
/// @return bool success for opening socket
bool openSocket();
bool openSocket() override;

/// @brief Close TCP Socket
/// @return bool success for closing socket
bool closeSocket();
bool closeSocket() override;

/// @brief Receive with a reference to a CanFrame to fill
/// @param frame OUTPUT CanFrame to fill
/// @return optional error string filled with an error message if any
std::optional<socket_error_string_t> receive(polymath::socketcan::CanFrame & can_frame);
std::optional<socket_error_string_t> receive(polymath::socketcan::CanFrame & can_frame) override;

/// @brief Receive returns the received CanFrame
/// @return optional CanFrame
Expand All @@ -87,30 +95,54 @@ class AxiomaticAdapter : public std::enable_shared_from_this<AxiomaticAdapter>

/// @brief Start a reception thread (calls callback)
/// @return success on started
bool startReceptionThread();
bool startReceptionThread() override;

/// @brief Stop and join reception thread
/// @param timeout_s INPUT timeout in seconds, <=0 means no timeout
/// @brief Stop and join reception thread (legacy ms-based overload).
/// @param timeout_s INPUT timeout in milliseconds, <=0 means no timeout
/// @return success on closed and joined thread
bool joinReceptionThread(const std::chrono::milliseconds & timeout_s = AxiomaticAdapter::JOIN_RECEPTION_TIMEOUT_MS);

/// @brief Stop and join reception thread (ICanBackend interface signature).
/// @param timeout_s INPUT timeout as a chrono::duration<float>; cast to ms internally.
/// @return success on closed and joined thread
bool joinReceptionThread(const std::chrono::duration<float> & timeout_s) override;

/// @brief Transmit a can frame via socket
/// @param frame INPUT const reference to the frame
/// @return optional error string filled with an error message if any
std::optional<socket_error_string_t> send(const polymath::socketcan::CanFrame & frame);
std::optional<socket_error_string_t> send(const polymath::socketcan::CanFrame & frame) override;

/// @brief Transmit a can frame via socket
/// @param frame INPUT shared_ptr to a frame to send (ICanBackend overload).
/// @return optional error string filled with an error message if any
std::optional<socket_error_string_t> send(const std::shared_ptr<const polymath::socketcan::CanFrame> frame) override;

/// @brief Transmit a can frame via socket
/// @param frame Linux CAN frame to send
/// @return optional error string filled with an error message if any
std::optional<socket_error_string_t> send(const can_frame & frame);

/// @brief Get state of socket
/// @return TCPSocketState data type detailing OPEN or CLOSED
TCPSocketState get_socket_state();
/// @return SocketState data type detailing OPEN or CLOSED
///
/// (TCPSocketState is now an alias of polymath::socketcan::SocketState, so
/// callers that hold the result as TCPSocketState continue to work.)
polymath::socketcan::SocketState get_socket_state() override;

/// @brief Checks if the receive thread is running
/// @return True if the thread is running, false otherwise
bool is_thread_running();
bool is_thread_running() override;

/// @brief Set the receive callback after construction (ICanBackend interface).
/// Set BEFORE calling startReceptionThread() to avoid racing the rx thread.
/// @return true on success.
bool setOnReceiveCallback(
std::function<void(std::unique_ptr<const polymath::socketcan::CanFrame> frame)> && callback_function) override;

/// @brief Set the error callback after construction (ICanBackend interface).
/// Set BEFORE calling startReceptionThread() to avoid racing the rx thread.
/// @return true on success.
bool setOnErrorCallback(std::function<void(socket_error_string_t error)> && callback_function) override;

private:
/// @brief use Implemention (pimpl) to avoid including boost/asio.hpp in header + linking in CMake
Expand Down
135 changes: 135 additions & 0 deletions axiomatic_adapter/include/axiomatic_adapter/axiomatic_fd_backend.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,135 @@
// Copyright (c) 2025-present Polymath Robotics, Inc. All rights reserved
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AXIOMATIC_ADAPTER__AXIOMATIC_FD_BACKEND_HPP_
#define AXIOMATIC_ADAPTER__AXIOMATIC_FD_BACKEND_HPP_

#include "axiomatic_adapter/axiomatic_protocol.hpp"
#include "axiomatic_adapter/udp_client.hpp"
#include "socketcan_adapter/can_frame.hpp"
#include "socketcan_adapter/i_can_backend.hpp"
#include "socketcan_adapter/socketcan_adapter.hpp" // for SocketState enum

#include <atomic>
#include <chrono>
#include <cstdint>
#include <functional>
#include <memory>
#include <mutex>
#include <optional>
#include <string>

namespace polymath
{
namespace can
{

/// @class polymath::can::AxiomaticFdBackend
/// @brief ICanBackend implementation for the Axiomatic AX140970 Dual CAN FD to
/// Ethernet converter (UDP transport).
///
/// Wraps polymath::axiomatic::UdpClient and translates between the Axiomatic
/// wire protocol (envelope + CAN FD Frame Stream, see axiomatic_protocol.hpp)
/// and the polymath::socketcan::CanFrame value type that ICanBackend exposes
/// to callers.
///
/// Classical-CAN ONLY in this revision. CanFrame currently wraps a Linux
/// `struct can_frame` with an 8-byte payload limit. The AX140970 itself
/// supports up to 64-byte CAN FD frames with BRS/ESI, but those cannot fit
/// through CanFrame yet. Until CanFrame is generalized (separate PR), this
/// backend drops inbound frames whose length > 8 or whose FDF flag is set;
/// those drops are counted on `fd_frames_dropped()` so callers can detect
/// the limitation rather than silently lose data.
///
/// Lifecycle mirrors the SocketcanAdapter pattern:
///
/// AxiomaticFdBackend backend(opts);
/// backend.openSocket(); // resolves + binds UDP socket
/// backend.setOnReceiveCallback(...); // optional; set before start
/// backend.setOnErrorCallback(...); // optional
/// backend.startReceptionThread(); // begins delivering callbacks
/// ...
/// backend.joinReceptionThread(timeout);
/// backend.closeSocket();
class AxiomaticFdBackend : public polymath::socketcan::ICanBackend
{
public:
using socket_error_string_t = polymath::socketcan::ICanBackend::socket_error_string_t;

struct Options
{
std::string device_ip;
uint16_t device_port = 4000;
/// Local channel address advertised in our heartbeats; the device uses
/// this to filter which CAN frames it forwards to us. Default (0,0) =
/// NULL filter = accept all.
polymath::axiomatic::ChannelAddress local_address{0u, 0u};
/// Destination address for transmitted frames. (CG=0, CIDS=0x1) is CAN1
/// in the device's default routing; (0, 0x2) is CAN2. Override per-channel.
polymath::axiomatic::ChannelAddress tx_address{0u, 0x1u};
std::chrono::milliseconds heartbeat_interval{1000};
};

explicit AxiomaticFdBackend(Options opts);
~AxiomaticFdBackend() override;

AxiomaticFdBackend(const AxiomaticFdBackend &) = delete;
AxiomaticFdBackend & operator=(const AxiomaticFdBackend &) = delete;

// ---- ICanBackend ----
bool openSocket() override;
bool closeSocket() override;
polymath::socketcan::SocketState get_socket_state() override;

std::optional<socket_error_string_t> send(
const std::shared_ptr<const polymath::socketcan::CanFrame> frame) override;
std::optional<socket_error_string_t> send(
const polymath::socketcan::CanFrame & frame) override;
std::optional<socket_error_string_t> receive(
polymath::socketcan::CanFrame & frame) override;

bool startReceptionThread() override;
bool joinReceptionThread(const std::chrono::duration<float> & timeout_s) override;
bool is_thread_running() override;

bool setOnReceiveCallback(
std::function<void(std::unique_ptr<const polymath::socketcan::CanFrame> frame)> &&
callback_function) override;
bool setOnErrorCallback(
std::function<void(socket_error_string_t error)> && callback_function) override;

/// @brief Count of inbound frames dropped because they exceed CanFrame's
/// 8-byte Classical-CAN payload limit (length > 8 or FDF flag set). When
/// CanFrame is generalized to CAN FD this will stay at 0.
uint64_t fd_frames_dropped() const noexcept;

private:
void onUdpFrame(const polymath::axiomatic::CanFdFrameRecord & frame);
void onUdpErrorFrame(uint8_t error_code);

Options opts_;
std::unique_ptr<polymath::axiomatic::UdpClient> udp_client_;
std::atomic<bool> rx_dispatch_active_{false};
std::atomic<uint64_t> fd_frames_dropped_{0};

std::mutex callback_mu_;
std::function<void(std::unique_ptr<const polymath::socketcan::CanFrame> frame)>
on_receive_;
std::function<void(socket_error_string_t error)> on_error_;
};

} // namespace can
} // namespace polymath

#endif // AXIOMATIC_ADAPTER__AXIOMATIC_FD_BACKEND_HPP_
Loading
Loading