Public Member Functions | Private Types | Private Member Functions | Private Attributes
can::DummyInterface Class Reference

#include <dummy.h>

Inheritance diagram for can::DummyInterface:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool add (const std::string &k, const Frame &v, bool multi)
bool add (const Frame &k, const Frame &v, bool multi)
bool add (const std::string &k, const std::string &v, bool multi)
bool add (const Frame &k, const std::string &v, bool multi)
virtual FrameListener::Ptr createMsgListener (const FrameDelegate &delegate)
virtual FrameListener::Ptr createMsgListener (const Frame::Header &h, const FrameDelegate &delegate)
virtual StateListener::Ptr createStateListener (const StateDelegate &delegate)
virtual bool doesLoopBack () const
 DummyInterface (bool loopback)
virtual State getState ()
bool init (const std::string &device, bool loopback)
virtual bool recover ()
virtual void run ()
virtual bool send (const Frame &msg)
virtual void shutdown ()
virtual bool translateError (unsigned int internal_error, std::string &str)

Private Types

typedef FilteredDispatcher
< const unsigned int,
CommInterface::FrameListener
FrameDispatcher
typedef
boost::unordered_multimap
< std::string, Frame
Map
typedef SimpleDispatcher
< StateInterface::StateListener
StateDispatcher

Private Member Functions

bool add_noconv (const std::string &k, const Frame &v, bool multi)

Private Attributes

FrameDispatcher frame_dispatcher_
bool loopback_
Map map_
State state_
StateDispatcher state_dispatcher_

Detailed Description

Definition at line 11 of file dummy.h.


Member Typedef Documentation

Definition at line 12 of file dummy.h.

typedef boost::unordered_multimap<std::string, Frame> can::DummyInterface::Map [private]

Definition at line 14 of file dummy.h.

Definition at line 13 of file dummy.h.


Constructor & Destructor Documentation

can::DummyInterface::DummyInterface ( bool  loopback) [inline]

Definition at line 29 of file dummy.h.


Member Function Documentation

bool can::DummyInterface::add ( const std::string &  k,
const Frame v,
bool  multi 
) [inline]

Definition at line 31 of file dummy.h.

bool can::DummyInterface::add ( const Frame k,
const Frame v,
bool  multi 
) [inline]

Definition at line 34 of file dummy.h.

bool can::DummyInterface::add ( const std::string &  k,
const std::string &  v,
bool  multi 
) [inline]

Definition at line 37 of file dummy.h.

bool can::DummyInterface::add ( const Frame k,
const std::string &  v,
bool  multi 
) [inline]

Definition at line 40 of file dummy.h.

bool can::DummyInterface::add_noconv ( const std::string &  k,
const Frame v,
bool  multi 
) [inline, private]

Definition at line 21 of file dummy.h.

virtual FrameListener::Ptr can::DummyInterface::createMsgListener ( const FrameDelegate delegate) [inline, virtual]

acquire a listener for the specified delegate, that will get called for all messages

Parameters:
[in]delegate,:delegate to be bound by the listener
Returns:
managed pointer to listener

Implements can::CommInterface.

Definition at line 56 of file dummy.h.

virtual FrameListener::Ptr can::DummyInterface::createMsgListener ( const Frame::Header ,
const FrameDelegate delegate 
) [inline, virtual]

acquire a listener for the specified delegate, that will get called for messages with demanded ID

Parameters:
[in]header,:CAN header to restrict listener on
[in]delegate,:delegate to be bound listener
Returns:
managed pointer to listener

Implements can::CommInterface.

Definition at line 59 of file dummy.h.

virtual StateListener::Ptr can::DummyInterface::createStateListener ( const StateDelegate delegate) [inline, virtual]

acquire a listener for the specified delegate, that will get called for all state changes

Parameters:
[in]delegate,:delegate to be bound by the listener
Returns:
managed pointer to listener

Implements can::StateInterface.

Definition at line 90 of file dummy.h.

virtual bool can::DummyInterface::doesLoopBack ( ) const [inline, virtual]

Implements can::DriverInterface.

Definition at line 78 of file dummy.h.

virtual State can::DummyInterface::getState ( ) [inline, virtual]
Returns:
current state of driver

Implements can::DriverInterface.

Definition at line 66 of file dummy.h.

bool can::DummyInterface::init ( const std::string &  device,
bool  loopback 
) [inline, virtual]

initialize interface

Parameters:
[in]device,:driver-specific device name/path
[in]loopback,:loop-back own messages
Returns:
true if device was initialized succesfully, false otherwise

Implements can::DriverInterface.

Definition at line 82 of file dummy.h.

virtual bool can::DummyInterface::recover ( ) [inline, virtual]

Recover interface after errors and emergency stops

Returns:
true if device was recovered succesfully, false otherwise

Implements can::DriverInterface.

Definition at line 64 of file dummy.h.

virtual void can::DummyInterface::run ( ) [inline, virtual]

Implements can::DriverInterface.

Definition at line 80 of file dummy.h.

virtual bool can::DummyInterface::send ( const Frame msg) [inline, virtual]

enqueue frame for sending

Parameters:
[in]msg,:message to be enqueued
Returns:
true if frame was enqueued succesfully, otherwise false

Implements can::CommInterface.

Definition at line 43 of file dummy.h.

virtual void can::DummyInterface::shutdown ( ) [inline, virtual]

shutdown interface

Returns:
true if shutdown was succesful, false otherwise

Implements can::DriverInterface.

Definition at line 68 of file dummy.h.

virtual bool can::DummyInterface::translateError ( unsigned int  internal_error,
std::string &  str 
) [inline, virtual]

Implements can::DriverInterface.

Definition at line 70 of file dummy.h.


Member Data Documentation

Definition at line 15 of file dummy.h.

Definition at line 19 of file dummy.h.

Definition at line 18 of file dummy.h.

Definition at line 17 of file dummy.h.

Definition at line 16 of file dummy.h.


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


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 20:43:53