15 #ifndef DRIVER_NODE_HPP_
16 #define DRIVER_NODE_HPP_
18 #include <rclcpp/rclcpp.hpp>
53 std::shared_ptr<lely::ev::Executor> exec,
54 std::shared_ptr<lely::canopen::AsyncMaster> master) = 0;
93 virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
108 explicit CanopenDriver(
const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
109 : rclcpp::Node(
"canopen_driver", node_options)
111 node_canopen_driver_ = std::make_shared<node_interfaces::NodeCanopenDriver<rclcpp::Node>>(
this);
136 std::shared_ptr<lely::ev::Executor> exec,
137 std::shared_ptr<lely::canopen::AsyncMaster> master)
override;
149 return rclcpp::Node::get_node_base_interface();
175 virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
196 : rclcpp_lifecycle::LifecycleNode(
"lifecycle_canopen_driver", node_options)
199 std::make_shared<node_interfaces::NodeCanopenDriver<rclcpp_lifecycle::LifecycleNode>>(
this);
223 std::shared_ptr<lely::ev::Executor> exec,
224 std::shared_ptr<lely::canopen::AsyncMaster> master)
override;
235 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(
236 const rclcpp_lifecycle::State & state);
246 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(
247 const rclcpp_lifecycle::State & state);
258 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(
259 const rclcpp_lifecycle::State & state);
270 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(
271 const rclcpp_lifecycle::State & state);
282 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(
283 const rclcpp_lifecycle::State & state);
295 return rclcpp_lifecycle::LifecycleNode::get_node_base_interface();
319 virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
Canopen Driver Interface.
Definition: driver_node.hpp:31
virtual void shutdown()=0
Shutdown the driver.
virtual std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > get_node_canopen_driver_interface()=0
Get the node canopen driver interface object.
virtual void set_master(std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master)=0
Set the master object.
virtual void init()=0
Initialise the driver.
virtual bool is_lifecycle()=0
Check whether this is a LifecycleNode.
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()=0
Get the node base interface object.
Canopen Driver.
Definition: driver_node.hpp:105
std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > node_canopen_driver_
Definition: driver_node.hpp:107
virtual std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > get_node_canopen_driver_interface()
Get the node canopen driver interface object.
Definition: driver_node.hpp:176
CanopenDriver(const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
Definition: driver_node.hpp:108
virtual void set_master(std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master) override
Set the master object.
virtual void shutdown() override
Shutdown the driver.
virtual void init() override
Initialise the driver.
virtual bool is_lifecycle() override
Check whether this is a LifecycleNode.
Definition: driver_node.hpp:166
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
Get the node base interface object.
Definition: driver_node.hpp:147
Lifecycle Canopen Driver.
Definition: driver_node.hpp:190
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
Get the node base interface object.
Definition: driver_node.hpp:293
virtual void init() override
Initialise the driver.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state)
Deactivate Callback.
virtual bool is_lifecycle() override
Check whether this is a LifecycleNode.
Definition: driver_node.hpp:311
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state)
Deactivate Callback.
virtual std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > get_node_canopen_driver_interface()
Get the node canopen driver interface object.
Definition: driver_node.hpp:320
virtual void set_master(std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master) override
Set the master object.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state)
Deactivate Callback.
virtual void shutdown() override
Shutdown the driver.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State &state)
Configure Callback.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State &state)
Activate Callback.
LifecycleCanopenDriver(const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
Definition: driver_node.hpp:195
std::shared_ptr< node_interfaces::NodeCanopenDriverInterface > node_canopen_driver_
Definition: driver_node.hpp:192
Definition: configuration_manager.hpp:28