ros2_canopen
master
C++ ROS CANopen Library
|
Lifecycle Canopen Driver. More...
#include <driver_node.hpp>
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::NodeCanopenDriverInterface > | get_node_canopen_driver_interface () |
Get the node canopen driver interface object. More... | |
Protected Attributes | |
std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > | node_canopen_driver_ |
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.
|
inlineexplicit |
|
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.
|
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.
exec | |
master |
Implements ros2_canopen::CanopenDriverInterface.
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_.
state |
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_.
state |
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_.
state |
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_.
state |
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_.
state |
|
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.
Implements ros2_canopen::CanopenDriverInterface.
|
overridevirtual |
Shutdown the driver.
This function will shutdown the driver by calling the shutdown() function of node_canopen_driver_.
Implements ros2_canopen::CanopenDriverInterface.
|
inlineoverridevirtual |
|
inlinevirtual |
Get the node canopen driver interface object.
This function gives access to the underlying NodeCanopenDriverInterface.
Implements ros2_canopen::CanopenDriverInterface.
|
protected |