#include <bcm_sync.h>
Public Member Functions | |
BCMsync (const std::string &device, boost::shared_ptr< can::SocketCANDriver > driver, const SyncProperties &sync_properties) | |
template<class T > | |
void | setIgnored (const T &other) |
template<class T > | |
void | setMonitored (const T &other) |
Static Public Attributes | |
static const uint32_t | ALL_NODES_MASK = 127 |
static const uint32_t | HEARTBEAT_ID = 0x700 |
static const uint32_t | NMT_ID = 0x000 |
Protected Member Functions | |
virtual void | handleDiag (LayerReport &report) |
virtual void | handleHalt (LayerStatus &status) |
virtual void | handleInit (LayerStatus &status) |
virtual void | handleRead (LayerStatus &status, const LayerState ¤t_state) |
virtual void | handleRecover (LayerStatus &status) |
virtual void | handleShutdown (LayerStatus &status) |
virtual void | handleWrite (LayerStatus &status, const LayerState ¤t_state) |
Private Member Functions | |
void | handleFrame (const can::Frame &frame) |
bool | skipNode (uint8_t id) |
Private Attributes | |
can::BCMsocket | bcm_ |
std::string | device_ |
boost::shared_ptr < can::SocketCANDriver > | driver_ |
can::CommInterface::FrameListener::Ptr | handler_ |
std::set< int > | ignored_nodes_ |
std::set< int > | known_nodes_ |
std::set< int > | monitored_nodes_ |
boost::mutex | mutex_ |
std::set< int > | started_nodes_ |
std::vector< can::Frame > | sync_frames_ |
uint16_t | sync_ms_ |
bool | sync_running_ |
Definition at line 21 of file bcm_sync.h.
canopen::BCMsync::BCMsync | ( | const std::string & | device, |
boost::shared_ptr< can::SocketCANDriver > | driver, | ||
const SyncProperties & | sync_properties | ||
) | [inline] |
Definition at line 143 of file bcm_sync.h.
virtual void canopen::BCMsync::handleDiag | ( | LayerReport & | report | ) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 86 of file bcm_sync.h.
void canopen::BCMsync::handleFrame | ( | const can::Frame & | frame | ) | [inline, private] |
Definition at line 46 of file bcm_sync.h.
virtual void canopen::BCMsync::handleHalt | ( | LayerStatus & | status | ) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 125 of file bcm_sync.h.
virtual void canopen::BCMsync::handleInit | ( | LayerStatus & | status | ) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 95 of file bcm_sync.h.
virtual void canopen::BCMsync::handleRead | ( | LayerStatus & | status, |
const LayerState & | current_state | ||
) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 78 of file bcm_sync.h.
virtual void canopen::BCMsync::handleRecover | ( | LayerStatus & | status | ) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 134 of file bcm_sync.h.
virtual void canopen::BCMsync::handleShutdown | ( | LayerStatus & | status | ) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 119 of file bcm_sync.h.
virtual void canopen::BCMsync::handleWrite | ( | LayerStatus & | status, |
const LayerState & | current_state | ||
) | [inline, protected, virtual] |
Implements canopen::Layer.
Definition at line 82 of file bcm_sync.h.
void canopen::BCMsync::setIgnored | ( | const T & | other | ) | [inline] |
Definition at line 160 of file bcm_sync.h.
void canopen::BCMsync::setMonitored | ( | const T & | other | ) | [inline] |
Definition at line 156 of file bcm_sync.h.
bool canopen::BCMsync::skipNode | ( | uint8_t | id | ) | [inline, private] |
Definition at line 39 of file bcm_sync.h.
const uint32_t canopen::BCMsync::ALL_NODES_MASK = 127 [static] |
Definition at line 139 of file bcm_sync.h.
can::BCMsocket canopen::BCMsync::bcm_ [private] |
Definition at line 32 of file bcm_sync.h.
std::string canopen::BCMsync::device_ [private] |
Definition at line 24 of file bcm_sync.h.
boost::shared_ptr<can::SocketCANDriver> canopen::BCMsync::driver_ [private] |
Definition at line 33 of file bcm_sync.h.
Definition at line 35 of file bcm_sync.h.
const uint32_t canopen::BCMsync::HEARTBEAT_ID = 0x700 [static] |
Definition at line 140 of file bcm_sync.h.
std::set<int> canopen::BCMsync::ignored_nodes_ [private] |
Definition at line 26 of file bcm_sync.h.
std::set<int> canopen::BCMsync::known_nodes_ [private] |
Definition at line 28 of file bcm_sync.h.
std::set<int> canopen::BCMsync::monitored_nodes_ [private] |
Definition at line 27 of file bcm_sync.h.
boost::mutex canopen::BCMsync::mutex_ [private] |
Definition at line 22 of file bcm_sync.h.
const uint32_t canopen::BCMsync::NMT_ID = 0x000 [static] |
Definition at line 141 of file bcm_sync.h.
std::set<int> canopen::BCMsync::started_nodes_ [private] |
Definition at line 29 of file bcm_sync.h.
std::vector<can::Frame> canopen::BCMsync::sync_frames_ [private] |
Definition at line 37 of file bcm_sync.h.
uint16_t canopen::BCMsync::sync_ms_ [private] |
Definition at line 34 of file bcm_sync.h.
bool canopen::BCMsync::sync_running_ [private] |
Definition at line 31 of file bcm_sync.h.