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

Node Canopen Driver. More...

#include <node_canopen_driver.hpp>

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

Public Member Functions

 NodeCanopenDriver (NODETYPE *node)
 
virtual void set_master (std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master)
 Set Master. More...
 
void init ()
 Initialise the driver. More...
 
virtual void init (bool called_from_base)
 Initialises the driver. More...
 
void configure ()
 Configure the driver. More...
 
virtual void configure (bool called_from_base)
 Configure the driver. More...
 
void activate ()
 Activate the driver. More...
 
virtual void activate (bool called_from_base)
 Activates the driver. More...
 
void deactivate ()
 Deactivate the driver. More...
 
virtual void deactivate (bool called_from_base)
 Deactivates the driver. More...
 
void cleanup ()
 Cleanup the driver. More...
 
virtual void cleanup (bool called_from_base)
 Cleanup the driver. More...
 
void shutdown ()
 Shutdown the driver. More...
 
virtual void shutdown (bool called_from_base)
 Shuts down the driver. More...
 
virtual void demand_set_master ()
 Demand set Master. More...
 
- Public Member Functions inherited from ros2_canopen::node_interfaces::NodeCanopenDriverInterface
 NodeCanopenDriverInterface ()
 

Protected Member Functions

virtual void add_to_master ()
 Add the driver to master. More...
 
virtual void remove_from_master ()
 Remove the driver from master. More...
 

Protected Attributes

NODETYPE * node_
 
std::shared_ptr< lely::ev::Executor > exec_
 
std::shared_ptr< lely::canopen::AsyncMaster > master_
 
std::shared_ptr< lely::canopen::BasicDriver > driver_
 
std::chrono::milliseconds non_transmit_timeout_
 
YAML::Node config_
 
uint8_t node_id_
 
std::string container_name_
 
std::string eds_
 
std::string bin_
 
rclcpp::CallbackGroup::SharedPtr client_cbg_
 
rclcpp::CallbackGroup::SharedPtr timer_cbg_
 
std::atomic< bool > master_set_
 
std::atomic< bool > initialised_
 
std::atomic< bool > configured_
 
std::atomic< bool > activated_
 

Detailed Description

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

Node Canopen Driver.

This class implements the NodeCanopenDriverInterface. It provides core functionality and logic for CanopenDriver, 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

◆ NodeCanopenDriver()

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

Member Function Documentation

◆ set_master()

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::set_master ( std::shared_ptr< lely::ev::Executor >  exec,
std::shared_ptr< lely::canopen::AsyncMaster >  master 
)
inlinevirtual

Set Master.

Sets the Lely Canopen Master Objects needed by the driver to add itself to the master.

Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.

◆ init() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::init ( )
inlinevirtual

Initialise the driver.

In this function the ROS interface should be created and potentially necessary callback groups.

Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.

◆ init() [2/2]

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

Initialises the driver.

This does not do anything, it is an empty function. it should be overridden by derived classes.

Todo:
Potentially make this an abstract function. This is mainly for debugging purposes.
Parameters
called_from_base

Reimplemented in ros2_canopen::node_interfaces::NodeCanopenProxyDriver< NODETYPE >, ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.

◆ configure() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::configure ( )
inlinevirtual

Configure the driver.

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

This function reads the parameters container_name, non_transmit_timeout, node_id and config. Once done it will call the configure(bool) function that should be over

Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.

◆ configure() [2/2]

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

Configure the driver.

This function should be overridden by derived classes.

Parameters
called_from_base

Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.

◆ activate() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::activate ( )
inlinevirtual

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::NodeCanopenDriverInterface.

◆ activate() [2/2]

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

Activates the driver.

This function should be overridden by derived classes.

Parameters
called_from_base

Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.

◆ deactivate() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::deactivate ( )
inlinevirtual

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::NodeCanopenDriverInterface.

◆ deactivate() [2/2]

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

Deactivates the driver.

This function should be overridden by derived classes.

Parameters
called_from_base

Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.

◆ cleanup() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::cleanup ( )
inlinevirtual

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::NodeCanopenDriverInterface.

◆ cleanup() [2/2]

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

Cleanup the driver.

This function should be overridden by derived classes.

Parameters
called_from_base

Reimplemented in ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.

◆ shutdown() [1/2]

template<class NODETYPE >
void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::shutdown ( )
inlinevirtual

Shutdown the driver.

This function should shutdown the driver.

Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.

◆ shutdown() [2/2]

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

Shuts down the driver.

This function should be overridden by derived classes.

Parameters
called_from_base

Reimplemented in ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.

◆ demand_set_master()

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::demand_set_master ( )
virtual

Demand set Master.

This function should ask the drivers parent container to set the master objects. This should result in a call to set_master function.

Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.

◆ add_to_master()

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::add_to_master ( )
inlineprotectedvirtual

◆ remove_from_master()

template<class NODETYPE >
virtual void ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::remove_from_master ( )
inlineprotectedvirtual

Member Data Documentation

◆ node_

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

◆ exec_

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

◆ master_

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

◆ driver_

template<class NODETYPE >
std::shared_ptr<lely::canopen::BasicDriver> ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::driver_
protected

◆ non_transmit_timeout_

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

◆ config_

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

◆ node_id_

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

◆ container_name_

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

◆ eds_

template<class NODETYPE >
std::string ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::eds_
protected

◆ bin_

template<class NODETYPE >
std::string ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >::bin_
protected

◆ client_cbg_

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

◆ timer_cbg_

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

◆ master_set_

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

◆ initialised_

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

◆ configured_

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

◆ activated_

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

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