Class CanopenDriver
Defined in File driver_node.hpp
Inheritance Relationships
Base Types
public ros2_canopen::CanopenDriverInterface
(Class CanopenDriverInterface)public rclcpp::Node
Class Documentation
-
class CanopenDriver : public ros2_canopen::CanopenDriverInterface, public rclcpp::Node
Canopen Driver.
This provides a class, that driver nodes that are based on rclcpp::Node should be derived of. This class implements the ros2_canopen::CanopenDriverInterface.
Public Functions
-
inline explicit CanopenDriver(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 the init, configure, demand_set_master and activate of the NodeCanopenDriverInterface. If the function finishes without exception, the driver is activated and ready for use.
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 –
-
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:
false
-
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>
Public Members
-
std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> node_canopen_driver_
-
inline explicit CanopenDriver(const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())