roboligo
Loading...
Searching...
No Matches
ConnectorNode.hpp
Go to the documentation of this file.
1// Copyright 2026 Juan S. Cely G.
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// https://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 ROBOLIGO_CONNECTOR__CONNECTORNODE_HPP_
16#define ROBOLIGO_CONNECTOR__CONNECTORNODE_HPP_
17
18
19#include "pluginlib/class_loader.hpp"
20
21#include "rclcpp/macros.hpp"
22#include "rclcpp_lifecycle/lifecycle_node.hpp"
23
26
27namespace roboligo
28{
35 class ConnectorNode : public rclcpp_lifecycle::LifecycleNode
36 {
37 public:
38
39 RCLCPP_SMART_PTR_DEFINITIONS(ConnectorNode)
40 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
41
46 explicit ConnectorNode(
47 const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
48
52 virtual ~ConnectorNode();
53
59 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
60
66 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
67
73 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state);
74
80 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state);
81
87 CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state);
88
94 CallbackReturnT on_error(const rclcpp_lifecycle::State & state);
95
101 bool init(std::shared_ptr<RobotState> robot_state);
102
106 void reset_connector(void);
107
113 bool cycle(std::shared_ptr<RobotState> robot_state);
114
115 private:
116
117 std::shared_ptr<ConnectorBase> connector_ {nullptr};
118
119 const std::shared_ptr<const RobotState> robot_state_;
120
121 std::shared_ptr<pluginlib::ClassLoader<roboligo::ConnectorBase>> connector_loader_;
122 };
123
124} // namespace roboligo
125
126#endif // ROBOLIGO_CONNECTOR__CONNECTORNODE_HPP_
Base class for connector plugins that manage robot state transitions.
Definition ConnectorBase.hpp:38
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
Instructions on_shutdown state.
Definition ConnectorNode.cpp:110
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
Instructions on_activate state.
Definition ConnectorNode.cpp:92
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
Instructions on_deactivate state.
Definition ConnectorNode.cpp:98
CallbackReturnT on_error(const rclcpp_lifecycle::State &state)
Instructions on_error state.
Definition ConnectorNode.cpp:122
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
Instructions on_cleanup state.
Definition ConnectorNode.cpp:104
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
Instructions on_configure state.
Definition ConnectorNode.cpp:52
ConnectorNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for ConnectorNode.
Definition ConnectorNode.cpp:27
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition ConnectorNode.hpp:40
bool cycle(std::shared_ptr< RobotState > robot_state)
Method called cycle by cycle.
Definition ConnectorNode.cpp:135
void reset_connector(void)
Method called when the node will be destroyed.
Definition ConnectorNode.cpp:142
bool init(std::shared_ptr< RobotState > robot_state)
Method called when the node is initialize.
Definition ConnectorNode.cpp:128
Represents the state and configuration of a robot.
Definition RobotState.hpp:45
Definition ClassificationBase.hpp:28