Modulo 4.2.2
Loading...
Searching...
No Matches
LifecycleComponent.cpp
1#include "modulo_components/LifecycleComponent.hpp"
2
3using namespace modulo_core::communication;
4using namespace rclcpp_lifecycle;
5
6namespace modulo_components {
7
8LifecycleComponent::LifecycleComponent(const rclcpp::NodeOptions& node_options, const std::string& fallback_name)
9 : LifecycleNode(modulo_utils::parsing::parse_node_name(node_options, fallback_name), node_options),
10 ComponentInterface(std::make_shared<rclcpp::node_interfaces::NodeInterfaces<ALL_RCLCPP_NODE_INTERFACES>>(
11 LifecycleNode::get_node_base_interface(), LifecycleNode::get_node_clock_interface(),
12 LifecycleNode::get_node_graph_interface(), LifecycleNode::get_node_logging_interface(),
13 LifecycleNode::get_node_parameters_interface(), LifecycleNode::get_node_services_interface(),
14 LifecycleNode::get_node_time_source_interface(), LifecycleNode::get_node_timers_interface(),
15 LifecycleNode::get_node_topics_interface(), LifecycleNode::get_node_type_descriptions_interface(),
16 LifecycleNode::get_node_waitables_interface())) {}
17
18std::shared_ptr<state_representation::ParameterInterface>
19LifecycleComponent::get_parameter(const std::string& name) const {
21}
22
23void LifecycleComponent::step() {
24 try {
25 if (this->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
26 this->evaluate_periodic_callbacks();
27 this->on_step_callback();
28 this->publish_outputs();
29 }
30 this->publish_predicates();
31 } catch (const std::exception& ex) {
32 RCLCPP_ERROR_STREAM(this->get_logger(), "Failed to execute step function: " << ex.what());
33 // TODO handle error in lifecycle component
34 // this->raise_error();
35 }
36}
37
38node_interfaces::LifecycleNodeInterface::CallbackReturn LifecycleComponent::on_configure(const State& previous_state) {
39 RCLCPP_DEBUG(this->get_logger(), "on_configure called from previous state %s", previous_state.label().c_str());
40 if (previous_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) {
41 RCLCPP_WARN(get_logger(), "Invalid transition 'configure' from state %s.", previous_state.label().c_str());
42 return node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
43 }
44 if (!this->handle_configure()) {
45 RCLCPP_WARN(get_logger(), "Configuration failed! Reverting to the unconfigured state.");
46 // perform cleanup actions to ensure the component is unconfigured
47 if (this->handle_cleanup()) {
48 return node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
49 } else {
51 get_logger(),
52 "Could not revert to the unconfigured state! Entering into the error processing transition state.");
53 return node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
54 }
55 }
56 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
57}
58
59bool LifecycleComponent::handle_configure() {
60 bool result;
61 try {
63 } catch (const std::exception& ex) {
65 return false;
66 }
67 return result && this->configure_outputs();
68}
69
71 return true;
72}
73
74node_interfaces::LifecycleNodeInterface::CallbackReturn LifecycleComponent::on_cleanup(const State& previous_state) {
75 RCLCPP_DEBUG(this->get_logger(), "on_cleanup called from previous state %s", previous_state.label().c_str());
76 if (previous_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
77 RCLCPP_WARN(get_logger(), "Invalid transition 'cleanup' from state %s.", previous_state.label().c_str());
78 return node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
79 }
80 if (!this->handle_cleanup()) {
81 RCLCPP_ERROR(get_logger(), "Cleanup failed! Entering into the error processing transition state.");
82 return node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
83 }
84 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
85}
86
87bool LifecycleComponent::handle_cleanup() {
88 try {
89 return this->on_cleanup_callback();
90 } catch (const std::exception& ex) {
92 return false;
93 }
94}
95
97 return true;
98}
99
100node_interfaces::LifecycleNodeInterface::CallbackReturn LifecycleComponent::on_activate(const State& previous_state) {
101 RCLCPP_DEBUG(this->get_logger(), "on_activate called from previous state %s", previous_state.label().c_str());
102 if (previous_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
103 RCLCPP_WARN(get_logger(), "Invalid transition 'activate' from state %s.", previous_state.label().c_str());
104 return node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
105 }
106 if (!this->handle_activate()) {
107 RCLCPP_WARN(get_logger(), "Activation failed! Reverting to the inactive state.");
108 // perform deactivation actions to ensure the component is inactive
109 if (this->handle_deactivate()) {
110 return node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
111 } else {
113 get_logger(), "Could not revert to the inactive state! Entering into the error processing transition state.");
114 return node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
115 }
116 }
117 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
118}
119
120bool LifecycleComponent::handle_activate() {
121 bool result;
122 try {
124 } catch (const std::exception& ex) {
126 return false;
127 }
128 return result && this->activate_outputs();
129}
130
132 return true;
133}
134
135node_interfaces::LifecycleNodeInterface::CallbackReturn LifecycleComponent::on_deactivate(const State& previous_state) {
136 RCLCPP_DEBUG(this->get_logger(), "on_deactivate called from previous state %s", previous_state.label().c_str());
137 if (previous_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
138 RCLCPP_WARN(get_logger(), "Invalid transition 'deactivate' from state %s.", previous_state.label().c_str());
139 return node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
140 }
141 if (!this->handle_deactivate()) {
142 RCLCPP_ERROR(get_logger(), "Deactivation failed! Entering into the error processing transition state.");
143 return node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
144 }
145 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
146}
147
148bool LifecycleComponent::handle_deactivate() {
149 auto result = this->deactivate_outputs();
150 try {
151 return result && this->on_deactivate_callback();
152 } catch (const std::exception& ex) {
154 return false;
155 }
156}
157
159 return true;
160}
161
162node_interfaces::LifecycleNodeInterface::CallbackReturn LifecycleComponent::on_shutdown(const State& previous_state) {
163 RCLCPP_DEBUG(this->get_logger(), "on_shutdown called from previous state %s", previous_state.label().c_str());
164 switch (previous_state.id()) {
165 case lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED:
166 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
167 case lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE:
168 if (!this->handle_deactivate()) {
169 RCLCPP_DEBUG(get_logger(), "Shutdown failed during intermediate deactivation!");
170 break;
171 }
172 [[fallthrough]];
173 case lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE:
174 if (!this->handle_cleanup()) {
175 RCLCPP_DEBUG(get_logger(), "Shutdown failed during intermediate cleanup!");
176 break;
177 }
178 [[fallthrough]];
179 case lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED:
180 if (!this->handle_shutdown()) {
181 break;
182 }
183 // TODO: reset and finalize all needed properties
184 // this->handlers_.clear();
185 // this->daemons_.clear();
186 // this->parameters_.clear();
187 // this->shutdown_ = true;
188 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
189 default:
190 RCLCPP_WARN(get_logger(), "Invalid transition 'shutdown' from state %s.", previous_state.label().c_str());
191 break;
192 }
193 RCLCPP_ERROR(get_logger(), "Entering into the error processing transition state.");
194 return node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
195}
196
197bool LifecycleComponent::handle_shutdown() {
198 bool result;
199 try {
201 } catch (const std::exception& ex) {
203 return false;
204 }
205 return result && this->clear_signals();
206}
207
209 return true;
210}
211
212node_interfaces::LifecycleNodeInterface::CallbackReturn LifecycleComponent::on_error(const State& previous_state) {
213 RCLCPP_DEBUG(this->get_logger(), "on_error called from previous state %s", previous_state.label().c_str());
214 this->set_predicate("in_error_state", true);
215 bool error_handled;
216 try {
217 error_handled = this->handle_error();
218 } catch (const std::exception& ex) {
219 RCLCPP_DEBUG(this->get_logger(), "Exception caught during on_error handling: %s", ex.what());
220 error_handled = false;
221 }
222 if (!error_handled) {
223 RCLCPP_ERROR(get_logger(), "Error processing failed! Entering into the finalized state.");
224 // TODO: reset and finalize all needed properties
225 return node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
226 }
227 this->set_predicate("in_error_state", false);
228 return node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
229}
230
231bool LifecycleComponent::handle_error() {
232 return this->on_error_callback();
233}
234
236 return true;
237}
238
239bool LifecycleComponent::configure_outputs() {
240 bool success = true;
241 for (auto& [name, interface] : this->outputs_) {
242 try {
243 auto topic_name = this->get_parameter_value<std::string>(name + "_topic");
245 this->get_logger(), "Configuring output '" << name << "' with topic name '" << topic_name << "'.");
246 auto message_pair = interface->get_message_pair();
247 switch (message_pair->get_type()) {
248 case MessageType::BOOL: {
250 interface = std::make_shared<PublisherHandler<LifecyclePublisher<std_msgs::msg::Bool>, std_msgs::msg::Bool>>(
251 PublisherType::LIFECYCLE_PUBLISHER, publisher)
252 ->create_publisher_interface(message_pair);
253 break;
254 }
255 case MessageType::FLOAT64: {
256 auto publisher = this->create_publisher<std_msgs::msg::Float64>(topic_name, this->get_qos());
257 interface =
258 std::make_shared<PublisherHandler<LifecyclePublisher<std_msgs::msg::Float64>, std_msgs::msg::Float64>>(
259 PublisherType::LIFECYCLE_PUBLISHER, publisher)
260 ->create_publisher_interface(message_pair);
261 break;
262 }
263 case MessageType::FLOAT64_MULTI_ARRAY: {
264 auto publisher = this->create_publisher<std_msgs::msg::Float64MultiArray>(topic_name, this->get_qos());
265 interface = std::make_shared<PublisherHandler<
266 LifecyclePublisher<std_msgs::msg::Float64MultiArray>, std_msgs::msg::Float64MultiArray>>(
267 PublisherType::LIFECYCLE_PUBLISHER, publisher)
268 ->create_publisher_interface(message_pair);
269 break;
270 }
271 case MessageType::INT32: {
272 auto publisher = this->create_publisher<std_msgs::msg::Int32>(topic_name, this->get_qos());
273 interface =
274 std::make_shared<PublisherHandler<LifecyclePublisher<std_msgs::msg::Int32>, std_msgs::msg::Int32>>(
275 PublisherType::LIFECYCLE_PUBLISHER, publisher)
276 ->create_publisher_interface(message_pair);
277 break;
278 }
279 case MessageType::STRING: {
280 auto publisher = this->create_publisher<std_msgs::msg::String>(topic_name, this->get_qos());
281 interface =
282 std::make_shared<PublisherHandler<LifecyclePublisher<std_msgs::msg::String>, std_msgs::msg::String>>(
283 PublisherType::LIFECYCLE_PUBLISHER, publisher)
284 ->create_publisher_interface(message_pair);
285 break;
286 }
287 case MessageType::ENCODED_STATE: {
288 auto publisher = this->create_publisher<modulo_core::EncodedState>(topic_name, this->get_qos());
289 interface = std::make_shared<
290 PublisherHandler<LifecyclePublisher<modulo_core::EncodedState>, modulo_core::EncodedState>>(
291 PublisherType::LIFECYCLE_PUBLISHER, publisher)
292 ->create_publisher_interface(message_pair);
293 break;
294 }
295 case MessageType::CUSTOM_MESSAGE: {
296 interface = this->custom_output_configuration_callables_.at(name)(topic_name);
297 break;
298 }
299 }
300 } catch (const modulo_core::exceptions::CoreException& ex) {
301 success = false;
302 RCLCPP_ERROR_STREAM(this->get_logger(), "Failed to configure output '" << name << "': " << ex.what());
303 }
304 }
305 return success;
306}
307
308bool LifecycleComponent::clear_signals() {
309 RCLCPP_DEBUG(this->get_logger(), "Clearing all inputs and outputs.");
310 this->inputs_.clear();
311 this->outputs_.clear();
312 return true;
313}
314
315bool LifecycleComponent::activate_outputs() {
316 bool success = true;
317 for (auto const& [name, interface] : this->outputs_) {
318 try {
319 interface->activate();
320 } catch (const modulo_core::exceptions::CoreException& ex) {
321 success = false;
322 RCLCPP_ERROR_STREAM(this->get_logger(), "Failed to activate output '" << name << "': " << ex.what());
323 }
324 }
325 RCLCPP_DEBUG(this->get_logger(), "All outputs activated.");
326 return success;
327}
328
329bool LifecycleComponent::deactivate_outputs() {
330 bool success = true;
331 for (auto const& [name, interface] : this->outputs_) {
332 try {
333 interface->deactivate();
334 } catch (const modulo_core::exceptions::CoreException& ex) {
335 success = false;
336 RCLCPP_ERROR_STREAM(this->get_logger(), "Failed to deactivate output '" << name << "': " << ex.what());
337 }
338 }
339 RCLCPP_DEBUG(this->get_logger(), "All outputs deactivated.");
340 return success;
341}
342
343rclcpp_lifecycle::State LifecycleComponent::get_lifecycle_state() const {
344 return this->get_current_state();
345}
346}// namespace modulo_components
Base interface class for modulo components to wrap a ROS Node with custom behaviour.
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
virtual void on_step_callback()
Steps to execute periodically. To be redefined by derived Component classes.
void set_predicate(const std::string &predicate_name, bool predicate_value)
Set the value of the predicate given as parameter, if the predicate is not found does not do anything...
rclcpp::QoS get_qos() const
Getter of the Quality of Service attribute.
virtual bool on_shutdown_callback()
Steps to execute when shutting down the component.
virtual bool on_deactivate_callback()
Steps to execute when deactivating the component.
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
virtual bool on_activate_callback()
Steps to execute when activating the component.
virtual bool on_cleanup_callback()
Steps to execute when cleaning up the component.
LifecycleComponent(const rclcpp::NodeOptions &node_options, const std::string &fallback_name="LifecycleComponent")
Constructor from node options.
virtual bool on_error_callback()
Steps to execute when handling errors.
virtual bool on_configure_callback()
Steps to execute when configuring the component.
rclcpp_lifecycle::State get_lifecycle_state() const
Get the current lifecycle state of the component.
The PublisherHandler handles different types of ROS publishers to activate, deactivate and publish da...
A base class for all core exceptions.
Modulo components.
Definition Component.hpp:9
Modulo Core communication module for handling messages on publication and subscription interfaces.
Modulo Core.