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

Lifecycle Canopen Driver. More...

#include <driver_node.hpp>

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

Public Member Functions

 LifecycleCanopenDriver (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...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure (const rclcpp_lifecycle::State &state)
 Configure Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate (const rclcpp_lifecycle::State &state)
 Activate Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state)
 Deactivate Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state)
 Deactivate Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state)
 Deactivate Callback. More...
 
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...
 

Protected Attributes

std::shared_ptr< node_interfaces::NodeCanopenDriverInterfacenode_canopen_driver_
 

Detailed Description

Lifecycle Canopen Driver.

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

Constructor & Destructor Documentation

◆ LifecycleCanopenDriver()

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

Member Function Documentation

◆ init()

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

Initialise the driver.

This function will activate the driver using the instantiated node_canopen_driver_. It will call init() of the NodeCanopenDriverInterface. If the function finishes without exception, the driver can be configured.

Implements ros2_canopen::CanopenDriverInterface.

◆ set_master()

virtual void ros2_canopen::LifecycleCanopenDriver::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.

◆ on_configure()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleCanopenDriver::on_configure ( const rclcpp_lifecycle::State &  state)

Configure Callback.

This function will call configure() and demand_set_master() of the node_canopen_driver_.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_activate()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleCanopenDriver::on_activate ( const rclcpp_lifecycle::State &  state)

Activate Callback.

This function will call activate() of the node_canopen_driver_.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_deactivate()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleCanopenDriver::on_deactivate ( const rclcpp_lifecycle::State &  state)

Deactivate Callback.

This function will call deactivate() of the node_canopen_driver_.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_cleanup()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleCanopenDriver::on_cleanup ( const rclcpp_lifecycle::State &  state)

Deactivate Callback.

This function will call cleanup() of the node_canopen_driver_.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_shutdown()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleCanopenDriver::on_shutdown ( const rclcpp_lifecycle::State &  state)

Deactivate Callback.

This function will call shutdown() of the node_canopen_driver_.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ get_node_base_interface()

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ros2_canopen::LifecycleCanopenDriver::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::LifecycleCanopenDriver::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::LifecycleCanopenDriver::is_lifecycle ( )
inlineoverridevirtual

Check whether this is a LifecycleNode.

Returns
true

Implements ros2_canopen::CanopenDriverInterface.

◆ get_node_canopen_driver_interface()

virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> ros2_canopen::LifecycleCanopenDriver::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::LifecycleCanopenDriver::node_canopen_driver_
protected

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