Template Class NodeCanopenBaseDriver
Defined in File node_canopen_base_driver.hpp
Inheritance Relationships
Base Type
public NodeCanopenDriver< NODETYPE >
Class Documentation
-
template<class NODETYPE>
class NodeCanopenBaseDriver : public NodeCanopenDriver<NODETYPE> Public Functions
-
inline virtual ~NodeCanopenBaseDriver()
-
virtual void init(bool called_from_base)
-
virtual void configure(bool called_from_base)
-
virtual void activate(bool called_from_base)
-
virtual void deactivate(bool called_from_base)
-
virtual void cleanup(bool called_from_base)
-
virtual void shutdown(bool called_from_base)
-
virtual void add_to_master()
-
virtual void remove_from_master()
-
inline void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)
Register a callback for NMT state change.
- Parameters:
nmt_state_cb –
-
inline void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)
Register a callback for RPDO.
- Parameters:
rpdo_cb –
-
inline void register_emcy_cb(std::function<void(COEmcy, uint8_t)> emcy_cb)
Register a callback for EMCY.
- Parameters:
emcy_cb –
Protected Functions
-
virtual void poll_timer_callback()
-
void nmt_listener()
-
virtual void on_nmt(canopen::NmtState nmt_state)
-
void rdpo_listener()
-
virtual void on_rpdo(COData data)
-
void emcy_listener()
-
virtual void on_emcy(COEmcy emcy)
-
virtual void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper &stat)
Protected Attributes
-
std::thread nmt_state_publisher_thread_
-
std::thread rpdo_publisher_thread_
-
std::thread emcy_publisher_thread_
-
std::mutex driver_mutex_
-
std::shared_ptr<ros2_canopen::LelyDriverBridge> lely_driver_
-
uint32_t period_ms_
-
int sdo_timeout_ms_
-
bool polling_
-
std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb_
-
std::function<void(COData, uint8_t)> rpdo_cb_
-
std::function<void(COEmcy, uint8_t)> emcy_cb_
-
std::shared_ptr<ros2_canopen::SafeQueue<ros2_canopen::COEmcy>> emcy_queue_
-
std::shared_ptr<ros2_canopen::SafeQueue<ros2_canopen::COData>> rpdo_queue_
-
rclcpp::TimerBase::SharedPtr poll_timer_
-
std::atomic<bool> diagnostic_enabled_
-
uint32_t diagnostic_period_ms_
-
std::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_
-
std::shared_ptr<DiagnosticsCollector> diagnostic_collector_
-
inline virtual ~NodeCanopenBaseDriver()