Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
canopen::Node Class Reference

#include <canopen.h>

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

Public Types

using instead = can::DelegateHelper< StateFunc >
 
enum  State {
  Unknown = 255, BootUp = 0, Stopped = 4, Operational = 5,
  PreOperational = 127
}
 
using StateFunc = std::function< void(const State &)>
 
typedef can::Listener< const StateFunc, const State & > StateListener
 
typedef StateListener::ListenerConstSharedPtr StateListenerConstSharedPtr
 
- Public Types inherited from canopen::Layer
enum  LayerState {
  Off, Init, Shutdown, Error,
  Halt, Recover, Ready
}
 

Public Member Functions

StateListenerConstSharedPtr addStateListener (const StateFunc &s)
 
void enterState (const State &s)
 
template<typename T >
get (const ObjectDict::Key &k)
 
const State getState ()
 
const ObjectStorageSharedPtr getStorage ()
 
 Node (const can::CommInterfaceSharedPtr interface, const ObjectDictSharedPtr dict, uint8_t node_id, const SyncCounterSharedPtr sync=SyncCounterSharedPtr())
 
bool prepare ()
 
bool reset ()
 
bool reset_com ()
 
bool start ()
 
bool stop ()
 
- Public Member Functions inherited from canopen::Layer
void diag (LayerReport &report)
 
LayerState getLayerState ()
 
void halt (LayerStatus &status)
 
void init (LayerStatus &status)
 
 Layer (const std::string &n)
 
void read (LayerStatus &status)
 
void recover (LayerStatus &status)
 
void shutdown (LayerStatus &status)
 
void write (LayerStatus &status)
 
virtual ~Layer ()
 

Public Attributes

const uint8_t node_id_
 
- Public Attributes inherited from canopen::Layer
const std::string name
 

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 can::CommInterfaceSharedPtr interface_
 
boost::timed_mutex mutex
 
can::FrameListenerConstSharedPtr nmt_listener_
 
PDOMapper pdo_
 
SDOClient sdo_
 
State state_
 
can::SimpleDispatcher< StateListenerstate_dispatcher_
 
const SyncCounterSharedPtr sync_
 

Additional Inherited Members

Detailed Description

Definition at line 189 of file canopen.h.

Member Typedef Documentation

◆ instead

Definition at line 209 of file canopen.h.

◆ StateFunc

using canopen::Node::StateFunc = std::function<void(const State&)>

Definition at line 208 of file canopen.h.

◆ StateListener

Definition at line 211 of file canopen.h.

◆ StateListenerConstSharedPtr

Definition at line 212 of file canopen.h.

Member Enumeration Documentation

◆ State

Enumerator
Unknown 
BootUp 
Stopped 
Operational 
PreOperational 

Definition at line 191 of file canopen.h.

Constructor & Destructor Documentation

◆ Node()

Node::Node ( const can::CommInterfaceSharedPtr  interface,
const ObjectDictSharedPtr  dict,
uint8_t  node_id,
const SyncCounterSharedPtr  sync = SyncCounterSharedPtr() 
)

Definition at line 30 of file node.cpp.

Member Function Documentation

◆ addStateListener()

StateListenerConstSharedPtr canopen::Node::addStateListener ( const StateFunc s)
inline

Definition at line 214 of file canopen.h.

◆ checkHeartbeat()

bool Node::checkHeartbeat ( )
private

Definition at line 141 of file node.cpp.

◆ enterState()

void canopen::Node::enterState ( const State s)

◆ get()

template<typename T >
T canopen::Node::get ( const ObjectDict::Key k)
inline

Definition at line 218 of file canopen.h.

◆ getHeartbeatInterval()

uint16_t canopen::Node::getHeartbeatInterval ( )
inlineprivate

Definition at line 254 of file canopen.h.

◆ getState()

const Node::State Node::getState ( )

Definition at line 39 of file node.cpp.

◆ getStorage()

const ObjectStorageSharedPtr canopen::Node::getStorage ( )
inline

Definition at line 200 of file canopen.h.

◆ handleDiag()

void Node::handleDiag ( LayerReport report)
privatevirtual

Implements canopen::Layer.

Definition at line 167 of file node.cpp.

◆ handleHalt()

void Node::handleHalt ( LayerStatus status)
privatevirtual

Implements canopen::Layer.

Definition at line 216 of file node.cpp.

◆ handleInit()

void Node::handleInit ( LayerStatus status)
privatevirtual

Implements canopen::Layer.

Definition at line 176 of file node.cpp.

◆ handleNMT()

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

Definition at line 115 of file node.cpp.

◆ handleRead()

void Node::handleRead ( LayerStatus status,
const LayerState current_state 
)
privatevirtual

Implements canopen::Layer.

Definition at line 148 of file node.cpp.

◆ handleRecover()

void Node::handleRecover ( LayerStatus status)
privatevirtual

Implements canopen::Layer.

Definition at line 202 of file node.cpp.

◆ handleShutdown()

void Node::handleShutdown ( LayerStatus status)
privatevirtual

Implements canopen::Layer.

Definition at line 210 of file node.cpp.

◆ handleWrite()

void Node::handleWrite ( LayerStatus status,
const LayerState current_state 
)
privatevirtual

Implements canopen::Layer.

Definition at line 159 of file node.cpp.

◆ prepare()

bool Node::prepare ( )

Definition at line 68 of file node.cpp.

◆ reset()

bool Node::reset ( )

Definition at line 55 of file node.cpp.

◆ reset_com()

bool Node::reset_com ( )

Definition at line 44 of file node.cpp.

◆ setHeartbeatInterval()

void canopen::Node::setHeartbeatInterval ( )
inlineprivate

Definition at line 255 of file canopen.h.

◆ start()

bool Node::start ( )

Definition at line 76 of file node.cpp.

◆ stop()

bool Node::stop ( )

Definition at line 84 of file node.cpp.

◆ switchState()

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

Definition at line 94 of file node.cpp.

◆ wait_for()

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

◆ cond

boost::condition_variable canopen::Node::cond
private

Definition at line 236 of file canopen.h.

◆ cond_mutex

boost::mutex canopen::Node::cond_mutex
private

Definition at line 235 of file canopen.h.

◆ heartbeat_

Definition at line 242 of file canopen.h.

◆ heartbeat_timeout_

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

Definition at line 253 of file canopen.h.

◆ interface_

const can::CommInterfaceSharedPtr canopen::Node::interface_
private

Definition at line 238 of file canopen.h.

◆ mutex

boost::timed_mutex canopen::Node::mutex
private

Definition at line 234 of file canopen.h.

◆ nmt_listener_

can::FrameListenerConstSharedPtr canopen::Node::nmt_listener_
private

Definition at line 240 of file canopen.h.

◆ node_id_

const uint8_t canopen::Node::node_id_

Definition at line 194 of file canopen.h.

◆ pdo_

PDOMapper canopen::Node::pdo_
private

Definition at line 251 of file canopen.h.

◆ sdo_

SDOClient canopen::Node::sdo_
private

Definition at line 250 of file canopen.h.

◆ state_

State canopen::Node::state_
private

Definition at line 249 of file canopen.h.

◆ state_dispatcher_

can::SimpleDispatcher<StateListener> canopen::Node::state_dispatcher_
private

Definition at line 244 of file canopen.h.

◆ sync_

const SyncCounterSharedPtr canopen::Node::sync_
private

Definition at line 239 of file canopen.h.


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


canopen_master
Author(s): Mathias Lüdtke
autogenerated on Mon Feb 28 2022 23:28:03