Class SocketcanAdapter

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< SocketcanAdapter >

Class Documentation

class SocketcanAdapter : public std::enable_shared_from_this<SocketcanAdapter>

Creates and manages a socketcan instance and simplifies the interface. Generally does not throw, but returns booleans to tell you success.

Public Types

using socket_error_string_t = std::string

Mapped to std lib, but should be remapped to Polymath Safety compatible versions.

using filter_vector_t = std::vector<struct can_filter>

Public Functions

SocketcanAdapter(const std::string &interface_name, const std::chrono::duration<float> &receive_timeout_s = SOCKET_RECEIVE_TIMEOUT_S)

SocketcanAdapter Class Init.

Parameters:

interface_name – Interface for the socket to initialize on

virtual ~SocketcanAdapter()

Destructor for SocketcanAdapter.

bool openSocket()

Open Socket.

Returns:

bool successfully opened socket

bool closeSocket()

Close Socket.

Returns:

bool successfully closed socket

std::optional<socket_error_string_t> setFilters(const filter_vector_t &filters, FilterMode mode = FilterMode::OVERWRITE)

Set a number of filters, vectorized.

Parameters:

filters – reference to a vector of can filters to set for the socket

Returns:

optional error string filled with an error message if any

std::optional<socket_error_string_t> setFilters(const std::shared_ptr<filter_vector_t> filters, FilterMode mode = FilterMode::OVERWRITE)

Set a number of filters, vectorized.

Shared ptr to a vector is technically more efficient than a vector of shared_ptrs TODO: Vectors are harder to justify in MISRA, so might want to use Array https://gitlab.com/polymathrobotics/polymath_core/-/issues/7

Parameters:

filters – INPUT shared ptr to a vector of can filters to set for the socket

Returns:

optional error string filled with an error message if any

std::optional<socket_error_string_t> setErrorMaskOverwrite(const can_err_mask_t &error_mask)

Set the error mask.

Parameters:

error_mask – INPUT error maskfor the socket to pass through

Returns:

optional string containing error information

std::optional<socket_error_string_t> setJoinOverwrite(const bool &join)

Set the socket to Join Filters and do a logical AND instead of OR.

Parameters:

error_mask – INPUT whether to set JOINED FILTERS

Returns:

optional string containing error information

std::optional<socket_error_string_t> receive(CanFrame &can_frame)

Receive with a reference to a CanFrame to fill.

Parameters:

frame – OUTPUT CanFrame to fill

Returns:

optional error string filled with an error message if any

std::optional<socket_error_string_t> receive(std::shared_ptr<CanFrame> frame)

Receive with a reference to a CanFrame to fill.

TODO: Switch to unique ptr https://gitlab.com/polymathrobotics/polymath_core/-/issues/8

Parameters:

frame – OUTPUT CanFrame to fill via shared_ptr

Returns:

optional error string filled with an error message if any

std::optional<const CanFrame> receive()

Receive returns the received CanFrame.

Returns:

optional CanFrame that was received by reference nullopt is returned if no canframe received, acts like null

bool startReceptionThread()

Start a reception thread (calls callback)

Returns:

success on started

bool joinReceptionThread(const std::chrono::duration<float> &timeout_s = JOIN_RECEPTION_TIMEOUT_S)

Stop and join reception thread.

Parameters:

timeout_s – INPUT timeout in seconds, <=0 means no timeout

Returns:

success on closed and joined thread

bool setOnReceiveCallback(std::function<void(std::unique_ptr<const CanFrame> frame)> &&callback_function)

Set receive callback function if thread is used.

Parameters:

callback_function – INPUT To be called on receipt of a can frame

Returns:

success on receive callback set

bool setOnErrorCallback(std::function<void(socket_error_string_t error)> &&callback_function)

Set receive callback function if thread is used.

Parameters:

callback_function – INPUT To be called on receipt of a can frame

Returns:

success on error callback set

std::optional<socket_error_string_t> send(const CanFrame &frame)

Transmit a can frame via socket.

Parameters:

frame – INPUT const reference to the frame

Returns:

optional error string filled with an error message if any

std::optional<socket_error_string_t> send(const std::shared_ptr<const CanFrame> frame)

Transmit a can frame via socket.

Parameters:

frame – INPUT shared_ptr to frame. Convert non-const to const by doing

 {c++}
std::shared_ptr<CanFrame> frame = std::make_shared<CanFrame>();
// do work on frame then lock the frame as const before sending
std::shared_ptr<const CanFrame> frame = frame

Returns:

optional error string filled with an error message if any

std::optional<socket_error_string_t> send(const can_frame &frame)

Transmit a can frame via socket.

Parameters:

frame – Linux CAN frame to send

Returns:

optional error string filled with an error message if any

void set_receive_timeout(const std::chrono::duration<float> &recive_timeout_s)

Set receive timeout.

Parameters:

reecive_timeout_s – std::chrono::duration<float> sets receive timeout in seconds

SocketState get_socket_state()

Get state of socket.

Returns:

SocketState data type detailing OPEN or CLOSED

std::string get_interface()

Get interface.

Returns:

Can interface

bool is_thread_running()

Checks if the receive thread is running.

Returns:

True if the thread is running, false otherwise