Skip to content

Commit c2b2cb9

Browse files
thebyohazardthebyohazard
authored and
thebyohazard
committed
Add example of lifecycle node having an error and needing reconfiguration
Signed-off-by: thebyohazard <[email protected]>
1 parent df9a85e commit c2b2cb9

File tree

2 files changed

+72
-1
lines changed

2 files changed

+72
-1
lines changed

lifecycle/src/lifecycle_service_client.cpp

+28
Original file line numberDiff line numberDiff line change
@@ -256,6 +256,34 @@ callee_script(std::shared_ptr<LifecycleServiceClient> lc_client)
256256
}
257257
}
258258

259+
// reconfigure it because it encountered an error
260+
{
261+
time_between_state_changes.sleep();
262+
if (!rclcpp::ok()) {
263+
return;
264+
}
265+
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) {
266+
return;
267+
}
268+
if (!lc_client->get_state()) {
269+
return;
270+
}
271+
}
272+
273+
// activate it yet again
274+
{
275+
time_between_state_changes.sleep();
276+
if (!rclcpp::ok()) {
277+
return;
278+
}
279+
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) {
280+
return;
281+
}
282+
if (!lc_client->get_state()) {
283+
return;
284+
}
285+
}
286+
259287
// and deactivate it again
260288
{
261289
time_between_state_changes.sleep();

lifecycle/src/lifecycle_talker.cpp

+44-1
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
6969
* Callback for walltimer. This function gets invoked by the timer
7070
* and executes the publishing.
7171
* For this demo, we ask the node for its current state. If the
72-
* lifecycle publisher is not activate, we still invoke publish, but
72+
* lifecycle publisher is not activated, we still invoke publish, but
7373
* the communication is blocked so that no messages is actually transferred.
7474
*/
7575
void
@@ -88,6 +88,15 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
8888
get_logger(), "Lifecycle publisher is active. Publishing: [%s]", msg->data.c_str());
8989
}
9090

91+
// Simulate the node having some error whilst active,
92+
// necessitating reconfiguration.
93+
// raise_error() can be called from an inactive or active state.
94+
if(count == 32){
95+
RCLCPP_ERROR(get_logger(),"An error has arisen in the node and it needs reconfiguration.");
96+
raise_error();
97+
return;
98+
}
99+
91100
// We independently from the current state call publish on the lifecycle
92101
// publisher.
93102
// Only if the publisher is in an active state, the message transfer is
@@ -262,6 +271,40 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
262271
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
263272
}
264273

274+
/// Transition callback for state error processing
275+
/**
276+
* on_error callback is being called when the lifecycle node
277+
* enters the "errorProcessing" state.
278+
* Depending on the return value of this function, the state machine
279+
* either invokes a transition to the "unconfigured" state or the
280+
* finalized state.
281+
* TRANSITION_CALLBACK_SUCCESS transitions to "unconfigured"
282+
* TRANSITION_CALLBACK_FAILURE transitions to "finalized"
283+
* TRANSITION_CALLBACK_ERROR or any uncaught exceptions to "finalized"
284+
*/
285+
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
286+
on_error(const rclcpp_lifecycle::State & state)
287+
{
288+
// We explicitly deactivate the lifecycle publisher.
289+
// Starting from this point, all messages are no longer
290+
// sent into the network.
291+
timer_.reset();
292+
pub_.reset();
293+
294+
RCUTILS_LOG_ERROR_NAMED(
295+
get_name(),
296+
"on error is called from state %s.",
297+
state.label().c_str());
298+
299+
// We return a success and hence invoke the transition to the next
300+
// step: "unconfigured".
301+
// If we returned TRANSITION_CALLBACK_FAILURE instead, the state machine
302+
// would go the "finalized" state.
303+
// In case of TRANSITION_CALLBACK_ERROR or any thrown exception within
304+
// this callback, the state machine also transitions to state "finalized".
305+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
306+
}
307+
265308
private:
266309
// We hold an instance of a lifecycle publisher. This lifecycle publisher
267310
// can be activated or deactivated regarding on which state the lifecycle node

0 commit comments

Comments
 (0)