Class CanopenDriverInterface

Inheritance Relationships

Derived Types

Class Documentation

class CanopenDriverInterface

Canopen Driver Interface.

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

Subclassed by ros2_canopen::CanopenDriver, ros2_canopen::LifecycleCanopenDriver

Public Functions

virtual void init() = 0

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.

virtual void set_master(std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master) = 0

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

virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() = 0

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

virtual void shutdown() = 0

Shutdown the driver.

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

virtual bool is_lifecycle() = 0

Check whether this is a LifecycleNode.

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

Returns:

true

Returns:

false

virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> get_node_canopen_driver_interface() = 0

Get the node canopen driver interface object.

This function gives access to the underlying NodeCanopenDriverInterface.

Returns:

std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>