Class LifecycleCanopenDriver
Defined in File driver_node.hpp
Inheritance Relationships
Base Types
public ros2_canopen::CanopenDriverInterface
(Class CanopenDriverInterface)public rclcpp_lifecycle::LifecycleNode
Class Documentation
-
class LifecycleCanopenDriver : public ros2_canopen::CanopenDriverInterface, public rclcpp_lifecycle::LifecycleNode
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.
Public Functions
-
inline explicit LifecycleCanopenDriver(const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
-
virtual void init() override
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.
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 –
-
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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
-
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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
-
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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
-
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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
-
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 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
-
inline virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
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() override
Shutdown the driver.
This function will shutdown the driver by calling the shutdown() function of node_canopen_driver_.
-
inline virtual bool is_lifecycle() override
Check whether this is a LifecycleNode.
- Returns:
true
-
inline virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> get_node_canopen_driver_interface()
Get the node canopen driver interface object.
This function gives access to the underlying NodeCanopenDriverInterface.
- Returns:
std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
Protected Attributes
-
std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> node_canopen_driver_
-
inline explicit LifecycleCanopenDriver(const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())