ros2_canopen  master
C++ ROS CANopen Library
driver_node.hpp
Go to the documentation of this file.
1 // Copyright 2022 Christoph Hellmann Santos
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef DRIVER_NODE_HPP_
16 #define DRIVER_NODE_HPP_
17 
18 #include <rclcpp/rclcpp.hpp>
20 
21 namespace ros2_canopen
22 {
31 {
32 public:
40  virtual void init() = 0;
41 
52  virtual void set_master(
53  std::shared_ptr<lely::ev::Executor> exec,
54  std::shared_ptr<lely::canopen::AsyncMaster> master) = 0;
55 
64  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() = 0;
65 
73  virtual void shutdown() = 0;
74 
84  virtual bool is_lifecycle() = 0;
85 
93  virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
95 };
96 
104 class CanopenDriver : public CanopenDriverInterface, public rclcpp::Node
105 {
106 public:
107  std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> node_canopen_driver_;
108  explicit CanopenDriver(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
109  : rclcpp::Node("canopen_driver", node_options)
110  {
111  node_canopen_driver_ = std::make_shared<node_interfaces::NodeCanopenDriver<rclcpp::Node>>(this);
112  }
113 
123  virtual void init() override;
124 
135  virtual void set_master(
136  std::shared_ptr<lely::ev::Executor> exec,
137  std::shared_ptr<lely::canopen::AsyncMaster> master) override;
138 
147  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
148  {
149  return rclcpp::Node::get_node_base_interface();
150  }
151 
159  virtual void shutdown() override;
160 
166  virtual bool is_lifecycle() override { return false; }
167 
175  virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
177  {
178  return node_canopen_driver_;
179  }
180 };
181 
189 class LifecycleCanopenDriver : public CanopenDriverInterface, public rclcpp_lifecycle::LifecycleNode
190 {
191 protected:
192  std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> node_canopen_driver_;
193 
194 public:
195  explicit LifecycleCanopenDriver(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
196  : rclcpp_lifecycle::LifecycleNode("lifecycle_canopen_driver", node_options)
197  {
199  std::make_shared<node_interfaces::NodeCanopenDriver<rclcpp_lifecycle::LifecycleNode>>(this);
200  }
210  virtual void init() override;
211 
222  virtual void set_master(
223  std::shared_ptr<lely::ev::Executor> exec,
224  std::shared_ptr<lely::canopen::AsyncMaster> master) override;
225 
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);
248 
258  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
259  const rclcpp_lifecycle::State & state);
260 
270  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
271  const rclcpp_lifecycle::State & state);
272 
282  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
283  const rclcpp_lifecycle::State & state);
284 
293  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
294  {
295  return rclcpp_lifecycle::LifecycleNode::get_node_base_interface();
296  }
297 
305  virtual void shutdown() override;
311  virtual bool is_lifecycle() override { return true; }
319  virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>
321  {
322  return node_canopen_driver_;
323  }
324 };
325 
326 } // namespace ros2_canopen
327 
328 #endif
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