#include <canopen.h>

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 > | |
| 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 ¤t_state) |
| virtual void | handleRecover (LayerStatus &status) |
| virtual void | handleShutdown (LayerStatus &status) |
| virtual void | handleWrite (LayerStatus &status, const LayerState ¤t_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_ |
| typedef fastdelegate::FastDelegate1<const State&> canopen::Node::StateDelegate |
| typedef can::Listener<const StateDelegate, const State&> canopen::Node::StateListener |
| enum canopen::Node::State |
| 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>() |
||
| ) |
| StateListener::Ptr canopen::Node::addStateListener | ( | const StateDelegate & | s | ) | [inline] |
| bool Node::checkHeartbeat | ( | ) | [private] |
| void canopen::Node::enterState | ( | const State & | s | ) |
| T canopen::Node::get | ( | const ObjectDict::Key & | k | ) | [inline] |
| uint16_t canopen::Node::getHeartbeatInterval | ( | ) | [inline, private] |
| const Node::State Node::getState | ( | ) |
| const boost::shared_ptr<ObjectStorage> canopen::Node::getStorage | ( | ) | [inline] |
| void Node::handleDiag | ( | LayerReport & | report | ) | [private, virtual] |
Implements canopen::Layer.
| void Node::handleHalt | ( | LayerStatus & | status | ) | [private, virtual] |
Implements canopen::Layer.
| void Node::handleInit | ( | LayerStatus & | status | ) | [private, virtual] |
Implements canopen::Layer.
| void Node::handleNMT | ( | const can::Frame & | msg | ) | [private] |
| void Node::handleRead | ( | LayerStatus & | status, |
| const LayerState & | current_state | ||
| ) | [private, virtual] |
Implements canopen::Layer.
| void Node::handleRecover | ( | LayerStatus & | status | ) | [private, virtual] |
Implements canopen::Layer.
| void Node::handleShutdown | ( | LayerStatus & | status | ) | [private, virtual] |
Implements canopen::Layer.
| void Node::handleWrite | ( | LayerStatus & | status, |
| const LayerState & | current_state | ||
| ) | [private, virtual] |
Implements canopen::Layer.
| bool Node::prepare | ( | ) |
| bool Node::reset | ( | ) |
| bool Node::reset_com | ( | ) |
| void canopen::Node::setHeartbeatInterval | ( | ) | [inline, private] |
| bool Node::start | ( | ) |
| bool Node::stop | ( | ) |
| void Node::switchState | ( | const uint8_t & | s | ) | [private] |
| int Node::wait_for | ( | const State & | s, |
| const T & | timeout | ||
| ) | [private] |
boost::condition_variable canopen::Node::cond [private] |
boost::mutex canopen::Node::cond_mutex [private] |
boost::chrono::high_resolution_clock::time_point canopen::Node::heartbeat_timeout_ [private] |
const boost::shared_ptr<can::CommInterface> canopen::Node::interface_ [private] |
boost::timed_mutex canopen::Node::mutex [private] |
| const uint8_t canopen::Node::node_id_ |
PDOMapper canopen::Node::pdo_ [private] |
SDOClient canopen::Node::sdo_ [private] |
State canopen::Node::state_ [private] |
const boost::shared_ptr<SyncCounter> canopen::Node::sync_ [private] |