14 #ifndef MASTER_NODE_HPP_
15 #define MASTER_NODE_HPP_
17 #include <rclcpp/rclcpp.hpp>
57 virtual std::shared_ptr<lely::canopen::AsyncMaster>
get_master() = 0;
101 explicit CanopenMaster(
const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())
102 : rclcpp::Node(
"canopen_master", node_options)
139 virtual std::shared_ptr<lely::canopen::AsyncMaster>
get_master()
override;
161 return rclcpp::Node::get_node_base_interface();
178 : rclcpp_lifecycle::LifecycleNode(
"lifecycle_canopen_master", node_options)
181 std::make_shared<node_interfaces::NodeCanopenMaster<rclcpp_lifecycle::LifecycleNode>>(
this);
214 virtual std::shared_ptr<lely::canopen::AsyncMaster>
get_master()
override;
234 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(
235 const rclcpp_lifecycle::State & state);
245 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(
246 const rclcpp_lifecycle::State & state);
256 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(
257 const rclcpp_lifecycle::State & state);
267 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(
268 const rclcpp_lifecycle::State & state);
278 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(
279 const rclcpp_lifecycle::State & state);
291 return rclcpp_lifecycle::LifecycleNode::get_node_base_interface();
Canopen Master Interface.
Definition: master_node.hpp:29
virtual std::shared_ptr< lely::ev::Executor > get_executor()=0
Get the executor object.
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()=0
Get the node base interface object.
virtual bool is_lifecycle()=0
Check whether the node is a lifecycle node.
virtual void shutdown()=0
Shutdown the driver.
virtual std::shared_ptr< lely::canopen::AsyncMaster > get_master()=0
Get the master object.
virtual void init()=0
Initialise the master.
Canopen Master.
Definition: master_node.hpp:98
std::shared_ptr< node_interfaces::NodeCanopenMasterInterface > node_canopen_master_
Definition: master_node.hpp:100
virtual std::shared_ptr< lely::ev::Executor > get_executor() override
Get the executor object.
CanopenMaster(const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
Definition: master_node.hpp:101
virtual void init() override
Initialises the driver.
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
Get the node base interface object.
Definition: master_node.hpp:159
virtual std::shared_ptr< lely::canopen::AsyncMaster > get_master() override
Get the master object.
virtual void shutdown() override
Shuts the master down.
virtual bool is_lifecycle()
Check whether the node is a lifecycle node.
Definition: master_node.hpp:168
Definition: master_node.hpp:172
virtual void shutdown() override
Shuts the master down.
virtual std::shared_ptr< lely::ev::Executor > get_executor() override
Get the executor object.
virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override
Get the node base interface object.
Definition: master_node.hpp:289
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state)
Shutdown Transition Callback.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State &state)
Activate Transition Callback.
virtual void init() override
Initialises the driver.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state)
Cleanup Transition Callback.
std::shared_ptr< node_interfaces::NodeCanopenMasterInterface > node_canopen_master_
Definition: master_node.hpp:174
LifecycleCanopenMaster(const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions())
Definition: master_node.hpp:177
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state)
Deactivet Transition Callback.
virtual bool is_lifecycle()
Check whether the node is a lifecycle node.
Definition: master_node.hpp:298
virtual std::shared_ptr< lely::canopen::AsyncMaster > get_master() override
Get the master object.
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State &state)
Configure Transition Callback.
Definition: configuration_manager.hpp:28