Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
canopen::Node Class Reference

#include <canopen.h>

Inheritance diagram for canopen::Node:
Inheritance graph
[legend]

List of all members.

Public Types

enum  State {
  Unknown = 255, BootUp = 0, Stopped = 4, Operational = 5,
  PreOperational = 127
}
typedef
fastdelegate::FastDelegate1
< const State & > 
StateDelegate
typedef can::Listener< const
StateDelegate, const State & > 
StateListener

Public Member Functions

StateListener::Ptr addStateListener (const StateDelegate &s)
void enterState (const State &s)
template<typename T >
get (const ObjectDict::Key &k)
const State getState ()
const boost::shared_ptr
< ObjectStorage
getStorage ()
 Node (const boost::shared_ptr< can::CommInterface > interface, const boost::shared_ptr< ObjectDict > dict, uint8_t node_id, const boost::shared_ptr< SyncCounter > sync=boost::shared_ptr< SyncCounter >())
bool prepare ()
bool reset ()
bool reset_com ()
bool start ()
bool stop ()

Public Attributes

const uint8_t node_id_

Private Member Functions

bool checkHeartbeat ()
uint16_t getHeartbeatInterval ()
virtual void handleDiag (LayerReport &report)
virtual void handleHalt (LayerStatus &status)
virtual void handleInit (LayerStatus &status)
void handleNMT (const can::Frame &msg)
virtual void handleRead (LayerStatus &status, const LayerState &current_state)
virtual void handleRecover (LayerStatus &status)
virtual void handleShutdown (LayerStatus &status)
virtual void handleWrite (LayerStatus &status, const LayerState &current_state)
void setHeartbeatInterval ()
void switchState (const uint8_t &s)
template<typename T >
int wait_for (const State &s, const T &timeout)

Private Attributes

boost::condition_variable cond
boost::mutex cond_mutex
ObjectStorage::Entry
< ObjectStorage::DataType
< ObjectDict::DEFTYPE_UNSIGNED16 >
::type > 
heartbeat_
boost::chrono::high_resolution_clock::time_point heartbeat_timeout_
const boost::shared_ptr
< can::CommInterface
interface_
boost::timed_mutex mutex
can::CommInterface::FrameListener::Ptr nmt_listener_
PDOMapper pdo_
SDOClient sdo_
State state_
can::SimpleDispatcher
< StateListener
state_dispatcher_
const boost::shared_ptr
< SyncCounter
sync_

Detailed Description

Definition at line 180 of file canopen.h.


Member Typedef Documentation

Definition at line 199 of file canopen.h.

Definition at line 200 of file canopen.h.


Member Enumeration Documentation

Enumerator:
Unknown 
BootUp 
Stopped 
Operational 
PreOperational 

Definition at line 182 of file canopen.h.


Constructor & Destructor Documentation

Node::Node ( const boost::shared_ptr< can::CommInterface interface,
const boost::shared_ptr< ObjectDict dict,
uint8_t  node_id,
const boost::shared_ptr< SyncCounter sync = boost::shared_ptr<SyncCounter>() 
)

Definition at line 30 of file node.cpp.


Member Function Documentation

Definition at line 202 of file canopen.h.

bool Node::checkHeartbeat ( ) [private]

Definition at line 141 of file node.cpp.

void canopen::Node::enterState ( const State s)
template<typename T >
T canopen::Node::get ( const ObjectDict::Key k) [inline]

Definition at line 206 of file canopen.h.

uint16_t canopen::Node::getHeartbeatInterval ( ) [inline, private]

Definition at line 242 of file canopen.h.

Definition at line 39 of file node.cpp.

const boost::shared_ptr<ObjectStorage> canopen::Node::getStorage ( ) [inline]

Definition at line 191 of file canopen.h.

void Node::handleDiag ( LayerReport report) [private, virtual]

Implements canopen::Layer.

Definition at line 167 of file node.cpp.

void Node::handleHalt ( LayerStatus status) [private, virtual]

Implements canopen::Layer.

Definition at line 216 of file node.cpp.

void Node::handleInit ( LayerStatus status) [private, virtual]

Implements canopen::Layer.

Definition at line 176 of file node.cpp.

void Node::handleNMT ( const can::Frame msg) [private]

Definition at line 115 of file node.cpp.

void Node::handleRead ( LayerStatus status,
const LayerState current_state 
) [private, virtual]

Implements canopen::Layer.

Definition at line 148 of file node.cpp.

void Node::handleRecover ( LayerStatus status) [private, virtual]

Implements canopen::Layer.

Definition at line 202 of file node.cpp.

void Node::handleShutdown ( LayerStatus status) [private, virtual]

Implements canopen::Layer.

Definition at line 210 of file node.cpp.

void Node::handleWrite ( LayerStatus status,
const LayerState current_state 
) [private, virtual]

Implements canopen::Layer.

Definition at line 159 of file node.cpp.

bool Node::prepare ( )

Definition at line 68 of file node.cpp.

bool Node::reset ( )

Definition at line 55 of file node.cpp.

bool Node::reset_com ( )

Definition at line 44 of file node.cpp.

void canopen::Node::setHeartbeatInterval ( ) [inline, private]

Definition at line 243 of file canopen.h.

bool Node::start ( )

Definition at line 76 of file node.cpp.

bool Node::stop ( )

Definition at line 84 of file node.cpp.

void Node::switchState ( const uint8_t &  s) [private]

Definition at line 94 of file node.cpp.

template<typename T >
int Node::wait_for ( const State s,
const T &  timeout 
) [private]

Definition at line 122 of file node.cpp.


Member Data Documentation

boost::condition_variable canopen::Node::cond [private]

Definition at line 224 of file canopen.h.

boost::mutex canopen::Node::cond_mutex [private]

Definition at line 223 of file canopen.h.

Definition at line 230 of file canopen.h.

boost::chrono::high_resolution_clock::time_point canopen::Node::heartbeat_timeout_ [private]

Definition at line 241 of file canopen.h.

const boost::shared_ptr<can::CommInterface> canopen::Node::interface_ [private]

Definition at line 226 of file canopen.h.

boost::timed_mutex canopen::Node::mutex [private]

Definition at line 222 of file canopen.h.

Definition at line 228 of file canopen.h.

const uint8_t canopen::Node::node_id_

Definition at line 185 of file canopen.h.

Definition at line 239 of file canopen.h.

Definition at line 238 of file canopen.h.

Definition at line 237 of file canopen.h.

Definition at line 232 of file canopen.h.

const boost::shared_ptr<SyncCounter> canopen::Node::sync_ [private]

Definition at line 227 of file canopen.h.


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


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