Class LifecycleCanopenMaster

Inheritance Relationships

Base Types

Class Documentation

class LifecycleCanopenMaster : public ros2_canopen::CanopenMasterInterface, public rclcpp_lifecycle::LifecycleNode

Public Functions

inline LifecycleCanopenMaster(const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
virtual void init() override

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.

virtual void shutdown() override

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.

virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master() override

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() override

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>

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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

inline virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override

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

inline virtual bool is_lifecycle()

Check whether the node is a lifecycle node.

Returns:

true

Protected Attributes

std::shared_ptr<node_interfaces::NodeCanopenMasterInterface> node_canopen_master_