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

Canopen Master Interface. More...

#include <master_node.hpp>

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

Public Member Functions

virtual void init ()=0
 Initialise the master. More...
 
virtual void shutdown ()=0
 Shutdown the driver. More...
 
virtual std::shared_ptr< lely::canopen::AsyncMaster > get_master ()=0
 Get the master object. More...
 
virtual std::shared_ptr< lely::ev::Executor > get_executor ()=0
 Get the executor object. More...
 
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ()=0
 Get the node base interface object. More...
 
virtual bool is_lifecycle ()=0
 Check whether the node is a lifecycle node. More...
 

Detailed Description

Canopen Master Interface.

This class provides the interface that all master's that are loaded by the device container need to implement.

Member Function Documentation

◆ init()

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

Initialise the master.

This function should initialise the master's functionality. It will be called by the device container after the node was added to the ros executor.

Implemented in ros2_canopen::LifecycleCanopenMaster, and ros2_canopen::CanopenMaster.

◆ shutdown()

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

Shutdown the driver.

This function should shutdown all functionality and make sure that the master will exit cleanly. It will be called by the device container before exiting.

Implemented in ros2_canopen::LifecycleCanopenMaster, and ros2_canopen::CanopenMaster.

◆ get_master()

virtual std::shared_ptr<lely::canopen::AsyncMaster> ros2_canopen::CanopenMasterInterface::get_master ( )
pure virtual

Get the master object.

This function should return the lely master object. It should throw a ros2_canopen::MasterException if the master object was not yet set.

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

Implemented in ros2_canopen::LifecycleCanopenMaster, and ros2_canopen::CanopenMaster.

◆ get_executor()

virtual std::shared_ptr<lely::ev::Executor> ros2_canopen::CanopenMasterInterface::get_executor ( )
pure virtual

Get the executor object.

This function gets the lely executor object. It should throw a ros2_canopen::MasterException if the executor object is not yet instantiated.

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

Implemented in ros2_canopen::LifecycleCanopenMaster, and ros2_canopen::CanopenMaster.

◆ get_node_base_interface()

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

Get the node base interface object.

This function should return the NodeBaseInterface of the associated ROS node. This is used by device container to add the master to the ros executor.

Returns
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr

Implemented in ros2_canopen::LifecycleCanopenMaster, and ros2_canopen::CanopenMaster.

◆ is_lifecycle()

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

Check whether the node is a lifecycle node.

Returns
true
false

Implemented in ros2_canopen::LifecycleCanopenMaster, and ros2_canopen::CanopenMaster.


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