ros2_canopen  master
C++ ROS CANopen Library
Public Member Functions | Protected Attributes | List of all members
ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE > Class Template Reference

Node Canopen Master. More...

#include <node_canopen_master.hpp>

Inheritance diagram for ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >:
Inheritance graph
[legend]
Collaboration diagram for ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >:
Collaboration graph
[legend]

Public Member Functions

 NodeCanopenMaster (NODETYPE *node)
 
void init () override
 Initialise Master. More...
 
virtual void init (bool called_from_base)
 
void configure () override
 Configure the driver. More...
 
virtual void configure (bool called_from_base)
 
void activate () override
 Activate the driver. More...
 
virtual void activate (bool called_from_base)
 Activate hook for derived classes. More...
 
void deactivate () override
 Deactivate the driver. More...
 
virtual void deactivate (bool called_from_base)
 Deactivate hook for derived classes. More...
 
void cleanup () override
 Cleanup the driver. More...
 
virtual void cleanup (bool called_from_base)
 
void shutdown () override
 Shutdown the driver. More...
 
virtual void shutdown (bool called_from_base)
 
virtual std::shared_ptr< lely::canopen::AsyncMaster > get_master ()
 Get the master object. More...
 
virtual std::shared_ptr< lely::ev::Executor > get_executor ()
 Get the executor object. More...
 

Protected Attributes

NODETYPE * node_
 
std::atomic< bool > initialised_
 
std::atomic< bool > configured_
 
std::atomic< bool > activated_
 
std::atomic< bool > master_set_
 
std::shared_ptr< lely::canopen::AsyncMaster > master_
 
std::shared_ptr< lely::ev::Executor > exec_
 
std::unique_ptr< lely::io::IoGuard > io_guard_
 
std::unique_ptr< lely::io::Context > ctx_
 
std::unique_ptr< lely::io::Poll > poll_
 
std::unique_ptr< lely::ev::Loop > loop_
 
std::unique_ptr< lely::io::Timer > timer_
 
std::unique_ptr< lely::io::CanController > ctrl_
 
std::unique_ptr< lely::io::CanChannel > chan_
 
std::unique_ptr< lely::io::SignalSet > sigset_
 
rclcpp::CallbackGroup::SharedPtr client_cbg_
 
rclcpp::CallbackGroup::SharedPtr timer_cbg_
 
YAML::Node config_
 
uint8_t node_id_
 
std::chrono::milliseconds non_transmit_timeout_
 
std::string container_name_
 
std::string master_dcf_
 
std::string master_bin_
 
std::string can_interface_name_
 
uint32_t timeout_
 
std::thread spinner_
 

Detailed Description

template<class NODETYPE>
class ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >

Node Canopen Master.

This class implements the NodeCanopenMasterInterface. It provides core functionality and logic for CanopenMaster, indepentently of the ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode and derived classes are supported. Other node types will lead to compile time error.

Template Parameters
NODETYPE

Constructor & Destructor Documentation

◆ NodeCanopenMaster()

template<class NODETYPE >
ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::NodeCanopenMaster ( NODETYPE *  node)
inline

Member Function Documentation

◆ init() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::init ( )
inlineoverridevirtual

◆ init() [2/2]

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::init ( bool  called_from_base)
inlinevirtual

◆ configure() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::configure ( )
inlineoverridevirtual

Configure the driver.

This function should contain the configuration related things, such as reading parameter data or configuration data from files.

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

◆ configure() [2/2]

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::configure ( bool  called_from_base)
inlinevirtual

◆ activate() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::activate ( )
inlineoverridevirtual

Activate the driver.

This function should activate the driver, consequently it needs to start all timers and threads necessary for the operation of the driver.

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

◆ activate() [2/2]

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::activate ( bool  called_from_base)
inlinevirtual

Activate hook for derived classes.

This function should create a Master using exec_, timer_, master_dcf_, master_bin_ and node_id_ members and store it in master_. It should also create a thread and run the master's event loop.

Parameters
called_from_base

◆ deactivate() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::deactivate ( )
inlineoverridevirtual

Deactivate the driver.

This function should deactivate the driver, consequently it needs to stop all timers and threads that are related to the operation of the diver.

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

◆ deactivate() [2/2]

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::deactivate ( bool  called_from_base)
inlinevirtual

Deactivate hook for derived classes.

This function should wait to join the thread created in the activate function.

Parameters
called_from_base

◆ cleanup() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::cleanup ( )
inlineoverridevirtual

Cleanup the driver.

This function needs to clean the internal state of the driver. This means all data should be deleted.

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

◆ cleanup() [2/2]

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::cleanup ( bool  called_from_base)
inlinevirtual

◆ shutdown() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::shutdown ( )
inlineoverridevirtual

Shutdown the driver.

This function should shutdown the driver.

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

◆ shutdown() [2/2]

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::shutdown ( bool  called_from_base)
inlinevirtual

◆ get_master()

template<class NODETYPE >
virtual std::shared_ptr<lely::canopen::AsyncMaster> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::get_master ( )
inlinevirtual

Get the master object.

Returns
std::shared_ptr<lely::canopen::AsyncMaster>

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

◆ get_executor()

template<class NODETYPE >
virtual std::shared_ptr<lely::ev::Executor> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::get_executor ( )
inlinevirtual

Get the executor object.

Returns
std::shared_ptr<lely::canopen::Executor>

Implements ros2_canopen::node_interfaces::NodeCanopenMasterInterface.

Member Data Documentation

◆ node_

template<class NODETYPE >
NODETYPE* ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::node_
protected

◆ initialised_

template<class NODETYPE >
std::atomic<bool> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::initialised_
protected

◆ configured_

template<class NODETYPE >
std::atomic<bool> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::configured_
protected

◆ activated_

template<class NODETYPE >
std::atomic<bool> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::activated_
protected

◆ master_set_

template<class NODETYPE >
std::atomic<bool> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::master_set_
protected

◆ master_

template<class NODETYPE >
std::shared_ptr<lely::canopen::AsyncMaster> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::master_
protected

◆ exec_

template<class NODETYPE >
std::shared_ptr<lely::ev::Executor> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::exec_
protected

◆ io_guard_

template<class NODETYPE >
std::unique_ptr<lely::io::IoGuard> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::io_guard_
protected

◆ ctx_

template<class NODETYPE >
std::unique_ptr<lely::io::Context> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::ctx_
protected

◆ poll_

template<class NODETYPE >
std::unique_ptr<lely::io::Poll> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::poll_
protected

◆ loop_

template<class NODETYPE >
std::unique_ptr<lely::ev::Loop> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::loop_
protected

◆ timer_

template<class NODETYPE >
std::unique_ptr<lely::io::Timer> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::timer_
protected

◆ ctrl_

template<class NODETYPE >
std::unique_ptr<lely::io::CanController> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::ctrl_
protected

◆ chan_

template<class NODETYPE >
std::unique_ptr<lely::io::CanChannel> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::chan_
protected

◆ sigset_

template<class NODETYPE >
std::unique_ptr<lely::io::SignalSet> ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::sigset_
protected

◆ client_cbg_

template<class NODETYPE >
rclcpp::CallbackGroup::SharedPtr ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::client_cbg_
protected

◆ timer_cbg_

template<class NODETYPE >
rclcpp::CallbackGroup::SharedPtr ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::timer_cbg_
protected

◆ config_

template<class NODETYPE >
YAML::Node ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::config_
protected

◆ node_id_

template<class NODETYPE >
uint8_t ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::node_id_
protected

◆ non_transmit_timeout_

template<class NODETYPE >
std::chrono::milliseconds ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::non_transmit_timeout_
protected

◆ container_name_

template<class NODETYPE >
std::string ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::container_name_
protected

◆ master_dcf_

template<class NODETYPE >
std::string ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::master_dcf_
protected

◆ master_bin_

template<class NODETYPE >
std::string ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::master_bin_
protected

◆ can_interface_name_

template<class NODETYPE >
std::string ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::can_interface_name_
protected

◆ timeout_

template<class NODETYPE >
uint32_t ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::timeout_
protected

◆ spinner_

template<class NODETYPE >
std::thread ros2_canopen::node_interfaces::NodeCanopenMaster< NODETYPE >::spinner_
protected

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