ros2_canopen  master
C++ ROS CANopen Library
Public Member Functions | List of all members
ros2_canopen::CanopenDriverInterface Class Referenceabstract

Canopen Driver Interface. More...

#include <driver_node.hpp>

Inheritance diagram for ros2_canopen::CanopenDriverInterface:
Inheritance graph
[legend]

Public Member Functions

virtual void init ()=0
 Initialise the driver. More...
 
virtual void set_master (std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master)=0
 Set the master object. More...
 
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ()=0
 Get the node base interface object. More...
 
virtual void shutdown ()=0
 Shutdown the driver. More...
 
virtual bool is_lifecycle ()=0
 Check whether this is a LifecycleNode. More...
 
virtual std::shared_ptr< node_interfaces::NodeCanopenDriverInterfaceget_node_canopen_driver_interface ()=0
 Get the node canopen driver interface object. More...
 

Detailed Description

Canopen Driver Interface.

This provides an interface that all driver nodes that are loaded by ros2_canopen::DeviceContainer need to implement.

Member Function Documentation

◆ init()

virtual void ros2_canopen::CanopenDriverInterface::init ( )
pure virtual

Initialise the driver.

This function will initialise the drivers functionalities. It will be called by the device_container when the node has been added to the executor.

Implemented in ros2_canopen::LifecycleCanopenDriver, and ros2_canopen::CanopenDriver.

◆ set_master()

virtual void ros2_canopen::CanopenDriverInterface::set_master ( std::shared_ptr< lely::ev::Executor >  exec,
std::shared_ptr< lely::canopen::AsyncMaster >  master 
)
pure virtual

Set the master object.

This function will set the Canopen Master Objects that are necessary for the driver to be instantiated. It will be called by the device container when the init_driver service is invoked.

Parameters
exec
master

Implemented in ros2_canopen::LifecycleCanopenDriver, and ros2_canopen::CanopenDriver.

◆ get_node_base_interface()

virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ros2_canopen::CanopenDriverInterface::get_node_base_interface ( )
pure virtual

Get the node base interface object.

This function shall return an rclcpp::node_interfaces::NodeBaseInterface::SharedPtr. The pointer will be used to add the driver node to the executor.

Returns
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr

Implemented in ros2_canopen::LifecycleCanopenDriver, and ros2_canopen::CanopenDriver.

◆ shutdown()

virtual void ros2_canopen::CanopenDriverInterface::shutdown ( )
pure virtual

Shutdown the driver.

This function will shutdown the driver and will especially join all threads to enable a clean shutdown.

Implemented in ros2_canopen::LifecycleCanopenDriver, and ros2_canopen::CanopenDriver.

◆ is_lifecycle()

virtual bool ros2_canopen::CanopenDriverInterface::is_lifecycle ( )
pure virtual

Check whether this is a LifecycleNode.

This function provides runtime information on whether the driver is a lifecycle driver or not.

Returns
true
false

Implemented in ros2_canopen::LifecycleCanopenDriver, and ros2_canopen::CanopenDriver.

◆ get_node_canopen_driver_interface()

virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> ros2_canopen::CanopenDriverInterface::get_node_canopen_driver_interface ( )
pure virtual

Get the node canopen driver interface object.

This function gives access to the underlying NodeCanopenDriverInterface.

Returns
std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>

Implemented in ros2_canopen::LifecycleCanopenDriver, and ros2_canopen::CanopenDriver.


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