ros2_canopen  master
C++ ROS CANopen Library
Public Member Functions | Public Attributes | List of all members
ros2_canopen::CanopenDriver Class Reference

Canopen Driver. More...

#include <driver_node.hpp>

Inheritance diagram for ros2_canopen::CanopenDriver:
Inheritance graph
[legend]
Collaboration diagram for ros2_canopen::CanopenDriver:
Collaboration graph
[legend]

Public Member Functions

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

Public Attributes

std::shared_ptr< node_interfaces::NodeCanopenDriverInterfacenode_canopen_driver_
 

Detailed Description

Canopen Driver.

This provides a class, that driver nodes that are based on rclcpp::Node should be derived of. This class implements the ros2_canopen::CanopenDriverInterface.

Constructor & Destructor Documentation

◆ CanopenDriver()

ros2_canopen::CanopenDriver::CanopenDriver ( const rclcpp::NodeOptions &  node_options = rclcpp::NodeOptions())
inlineexplicit

Member Function Documentation

◆ init()

virtual void ros2_canopen::CanopenDriver::init ( )
overridevirtual

Initialise the driver.

This function will activate the driver using the instantiated node_canopen_driver_. It will call the init, configure, demand_set_master and activate of the NodeCanopenDriverInterface. If the function finishes without exception, the driver is activated and ready for use.

Implements ros2_canopen::CanopenDriverInterface.

◆ set_master()

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

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

Implements ros2_canopen::CanopenDriverInterface.

◆ get_node_base_interface()

virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ros2_canopen::CanopenDriver::get_node_base_interface ( )
inlineoverridevirtual

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

Implements ros2_canopen::CanopenDriverInterface.

◆ shutdown()

virtual void ros2_canopen::CanopenDriver::shutdown ( )
overridevirtual

Shutdown the driver.

This function will shutdown the driver by calling the shutdown() function of node_canopen_driver_.

Implements ros2_canopen::CanopenDriverInterface.

◆ is_lifecycle()

virtual bool ros2_canopen::CanopenDriver::is_lifecycle ( )
inlineoverridevirtual

Check whether this is a LifecycleNode.

Returns
false

Implements ros2_canopen::CanopenDriverInterface.

◆ get_node_canopen_driver_interface()

virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> ros2_canopen::CanopenDriver::get_node_canopen_driver_interface ( )
inlinevirtual

Get the node canopen driver interface object.

This function gives access to the underlying NodeCanopenDriverInterface.

Returns
std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>

Implements ros2_canopen::CanopenDriverInterface.

Member Data Documentation

◆ node_canopen_driver_

std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> ros2_canopen::CanopenDriver::node_canopen_driver_

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