Public Member Functions | Public Attributes | Private Attributes | List of all members
can::SocketCAN Class Reference

#include <socketcan.h>

Public Member Functions

void close ()
 Close and unbind socket. More...
 
bool isOpen () const
 Returns whether the socket is open or closed. More...
 
bool open (const std::string &interface, boost::function< void(const can_frame &frame)> handler, int thread_priority)
 Open and bind socket. More...
 
 SocketCAN ()=default
 
bool startReceiverThread (int thread_priority)
 Starts a new thread, that will wait for socket events. More...
 
void write (can_frame *frame) const
 Sends the referenced frame to the bus. More...
 
 ~SocketCAN ()
 

Public Attributes

bool receiver_thread_running_ = false
 
boost::function< void(const can_frame &frame)> reception_handler
 
int sock_fd_ = -1
 
bool terminate_receiver_thread_ = false
 

Private Attributes

sockaddr_can address_ {}
 
ifreq interface_request_ {}
 
pthread_t receiver_thread_id_ {}
 

Detailed Description

Definition at line 79 of file socketcan.h.

Constructor & Destructor Documentation

◆ SocketCAN()

can::SocketCAN::SocketCAN ( )
default

◆ ~SocketCAN()

can::SocketCAN::~SocketCAN ( )

Definition at line 82 of file socketcan.cpp.

Member Function Documentation

◆ close()

void can::SocketCAN::close ( )

Close and unbind socket.

Definition at line 124 of file socketcan.cpp.

◆ isOpen()

bool can::SocketCAN::isOpen ( ) const

Returns whether the socket is open or closed.

Returns
True if socket has opened.

Definition at line 137 of file socketcan.cpp.

◆ open()

bool can::SocketCAN::open ( const std::string &  interface,
boost::function< void(const can_frame &frame)>  handler,
int  thread_priority 
)

Open and bind socket.

Parameters
interfacebus's name(example: can0).
handlerPointer to a function which shall be called when frames are being received from the CAN bus.
Returns
true if it successfully open and bind socket.

Definition at line 88 of file socketcan.cpp.

◆ startReceiverThread()

bool can::SocketCAN::startReceiverThread ( int  thread_priority)

Starts a new thread, that will wait for socket events.

Definition at line 193 of file socketcan.cpp.

◆ write()

void can::SocketCAN::write ( can_frame *  frame) const

Sends the referenced frame to the bus.

Parameters
framereferenced frame which you want to send.

Definition at line 142 of file socketcan.cpp.

Member Data Documentation

◆ address_

sockaddr_can can::SocketCAN::address_ {}
private

Definition at line 114 of file socketcan.h.

◆ interface_request_

ifreq can::SocketCAN::interface_request_ {}
private

Definition at line 113 of file socketcan.h.

◆ receiver_thread_id_

pthread_t can::SocketCAN::receiver_thread_id_ {}
private

Definition at line 115 of file socketcan.h.

◆ receiver_thread_running_

bool can::SocketCAN::receiver_thread_running_ = false

Definition at line 126 of file socketcan.h.

◆ reception_handler

boost::function<void(const can_frame& frame)> can::SocketCAN::reception_handler

Pointer to a function which shall be called when frames are being received from the CAN bus

Definition at line 161 of file socketcan.h.

◆ sock_fd_

int can::SocketCAN::sock_fd_ = -1

CAN socket file descriptor

Definition at line 121 of file socketcan.h.

◆ terminate_receiver_thread_

bool can::SocketCAN::terminate_receiver_thread_ = false

Request for the child thread to terminate

Definition at line 125 of file socketcan.h.


The documentation for this class was generated from the following files:


rm_hw
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:44