Class CanopenMasterInterface
Defined in File master_node.hpp
Inheritance Relationships
Derived Types
public ros2_canopen::CanopenMaster
(Class CanopenMaster)public ros2_canopen::LifecycleCanopenMaster
(Class LifecycleCanopenMaster)
Class Documentation
-
class CanopenMasterInterface
Canopen Master Interface.
This class provides the interface that all master’s that are loaded by the device container need to implement.
Subclassed by ros2_canopen::CanopenMaster, ros2_canopen::LifecycleCanopenMaster
Public Functions
-
virtual void init() = 0
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.
-
virtual void shutdown() = 0
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.
-
virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master() = 0
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>
-
virtual std::shared_ptr<lely::ev::Executor> get_executor() = 0
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>
-
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() = 0
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
-
virtual bool is_lifecycle() = 0
Check whether the node is a lifecycle node.
- Returns:
true
- Returns:
false
-
virtual void init() = 0