Public Member Functions | Private Member Functions | Private Attributes | List of all members
SocketCan Class Reference

#include <SocketCan.h>

Inheritance diagram for SocketCan:
Inheritance graph
[legend]

Public Member Functions

void init ()
 
bool init_ret ()
 
bool isObjectMode ()
 
bool receiveMsg (CanMsg *pCMsg)
 
bool receiveMsgRetry (CanMsg *pCMsg, int iNrOfRetry)
 
bool receiveMsgTimeout (CanMsg *pCMsg, int nMicroSecTimeout)
 
 SocketCan (const char *device, int baudrate)
 
 SocketCan (const char *device)
 
bool transmitMsg (CanMsg CMsg, bool bBlocking=true)
 
 ~SocketCan ()
 
- Public Member Functions inherited from CanItf
CanItfType getCanItfType ()
 
void setCanItfType (CanItfType iType)
 
virtual ~CanItf ()
 

Private Member Functions

void print_error (const can::State &state)
 

Private Attributes

bool m_bInitialized
 
can::ThreadedSocketCANInterfaceSharedPtr m_handle
 
can::BufferedReader m_reader
 
const char * p_cDevice
 

Additional Inherited Members

- Public Types inherited from CanItf
enum  CanItfType {
  CAN_PEAK = 0, CAN_PEAK_USB = 1, CAN_ESD = 2, CAN_DUMMY = 3,
  CAN_BECKHOFF = 4, CAN_SOCKETCAN = 5
}
 

Detailed Description

Definition at line 29 of file SocketCan.h.

Constructor & Destructor Documentation

SocketCan::SocketCan ( const char *  device,
int  baudrate 
)

Definition at line 28 of file SocketCan.cpp.

SocketCan::SocketCan ( const char *  device)

Definition at line 36 of file SocketCan.cpp.

SocketCan::~SocketCan ( )

Definition at line 45 of file SocketCan.cpp.

Member Function Documentation

void SocketCan::init ( )
virtual

Initializes the CAN bus.

Implements CanItf.

Definition at line 73 of file SocketCan.cpp.

bool SocketCan::init_ret ( )
virtual

Initializes the CAN bus and returns success.

Implements CanItf.

Definition at line 54 of file SocketCan.cpp.

bool SocketCan::isObjectMode ( )
inlinevirtual

Check if the current CAN interface was opened on OBJECT mode.

Returns
true if opened in OBJECT mode, false if not.

Implements CanItf.

Definition at line 42 of file SocketCan.h.

void SocketCan::print_error ( const can::State state)
private

Definition at line 167 of file SocketCan.cpp.

bool SocketCan::receiveMsg ( CanMsg pCMsg)
virtual

Reads a CAN message.

Returns
true if a message is available

Implements CanItf.

Definition at line 96 of file SocketCan.cpp.

bool SocketCan::receiveMsgRetry ( CanMsg pCMsg,
int  iNrOfRetry 
)
virtual

Reads a CAN message. The function blocks between the attempts.

Parameters
pCMsgCAN message
iNrOfRetrynumber of retries
Returns
true if a message is available

Implements CanItf.

Definition at line 118 of file SocketCan.cpp.

bool SocketCan::receiveMsgTimeout ( CanMsg pCMsg,
int  nMicroSecTimeout 
)
virtual

Reads a CAN message with timeout.

Parameters
pCMsgCAN message
nMicroSecTimeouttimeout in us
Returns
true if a message is available

Implements CanItf.

Definition at line 147 of file SocketCan.cpp.

bool SocketCan::transmitMsg ( CanMsg  CMsg,
bool  bBlocking = true 
)
virtual

Sends a CAN message.

Parameters
pCMsgCAN message
bBlockingspecifies whether send should be blocking or non-blocking

Implements CanItf.

Definition at line 84 of file SocketCan.cpp.

Member Data Documentation

bool SocketCan::m_bInitialized
private

Definition at line 51 of file SocketCan.h.

can::ThreadedSocketCANInterfaceSharedPtr SocketCan::m_handle
private

Definition at line 48 of file SocketCan.h.

can::BufferedReader SocketCan::m_reader
private

Definition at line 49 of file SocketCan.h.

const char* SocketCan::p_cDevice
private

Definition at line 52 of file SocketCan.h.


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


cob_generic_can
Author(s): Christian Connette
autogenerated on Wed Apr 7 2021 02:11:52