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

#include <master_node.hpp>

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

Public Member Functions

 LifecycleCanopenMaster (const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
 
virtual void init () override
 Initialises the driver. More...
 
virtual void shutdown () override
 Shuts the master down. More...
 
virtual std::shared_ptr< lely::canopen::AsyncMaster > get_master () override
 Get the master object. More...
 
virtual std::shared_ptr< lely::ev::Executor > get_executor () override
 Get the executor object. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure (const rclcpp_lifecycle::State &state)
 Configure Transition Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate (const rclcpp_lifecycle::State &state)
 Activate Transition Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state)
 Deactivet Transition Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state)
 Cleanup Transition Callback. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state)
 Shutdown Transition Callback. More...
 
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface () override
 Get the node base interface object. More...
 
virtual bool is_lifecycle ()
 Check whether the node is a lifecycle node. More...
 

Protected Attributes

std::shared_ptr< node_interfaces::NodeCanopenMasterInterfacenode_canopen_master_
 

Constructor & Destructor Documentation

◆ LifecycleCanopenMaster()

ros2_canopen::LifecycleCanopenMaster::LifecycleCanopenMaster ( const rclcpp::NodeOptions &  node_options = rclcpp::NodeOptions())
inline

Member Function Documentation

◆ init()

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

Initialises the driver.

This function initialises the driver. It is called by the device container after adding the node to the ros executor. This function uses the NodeCanopenMasterInterface. It will call init(). If this function does not throw, the driver is successfully initialised and ready to switch through the lifecycle.

Implements ros2_canopen::CanopenMasterInterface.

◆ shutdown()

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

Shuts the master down.

This function is called by the device container before exiting, it should enable a clean exit of the master and especially join all threads. It will call the shutdown() function of the NodeCanopenMasterInterface object associated with this class.

Implements ros2_canopen::CanopenMasterInterface.

◆ get_master()

virtual std::shared_ptr<lely::canopen::AsyncMaster> ros2_canopen::LifecycleCanopenMaster::get_master ( )
overridevirtual

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>

Implements ros2_canopen::CanopenMasterInterface.

◆ get_executor()

virtual std::shared_ptr<lely::ev::Executor> ros2_canopen::LifecycleCanopenMaster::get_executor ( )
overridevirtual

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>

Implements ros2_canopen::CanopenMasterInterface.

◆ on_configure()

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

Configure Transition Callback.

This function will call the configure() function of the NodeCanopenMasterInterface object associated with this class.

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

◆ on_activate()

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

Activate Transition Callback.

This function will call the active() function of the NodeCanopenMasterInterface object associated with this class.

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

◆ on_deactivate()

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

Deactivet Transition Callback.

This function will call the deactivate() function of the NodeCanopenMasterInterface object associated with this class.

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

◆ on_cleanup()

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

Cleanup Transition Callback.

This function will call the cleanup() function of the NodeCanopenMasterInterface object associated with this class.

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

◆ on_shutdown()

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

Shutdown Transition Callback.

This function will call the shutdown() function of the NodeCanopenMasterInterface object associated with this class.

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

◆ get_node_base_interface()

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

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

Implements ros2_canopen::CanopenMasterInterface.

◆ is_lifecycle()

virtual bool ros2_canopen::LifecycleCanopenMaster::is_lifecycle ( )
inlinevirtual

Check whether the node is a lifecycle node.

Returns
true

Implements ros2_canopen::CanopenMasterInterface.

Member Data Documentation

◆ node_canopen_master_

std::shared_ptr<node_interfaces::NodeCanopenMasterInterface> ros2_canopen::LifecycleCanopenMaster::node_canopen_master_
protected

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