Skip to content

Commit 3c45ac9

Browse files
author
Thomas Groechel
committed
Sq: Async+Cancelable Lifecycle Transitions
1 parent 3b34704 commit 3c45ac9

15 files changed

+1334
-9
lines changed

rclcpp_lifecycle/CMakeLists.txt

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ find_package(rosidl_typesupport_cpp REQUIRED)
2222

2323
### CPP High level library
2424
add_library(rclcpp_lifecycle
25+
src/change_state_handler_impl.cpp
2526
src/lifecycle_node.cpp
2627
src/lifecycle_node_entities_manager.cpp
2728
src/lifecycle_node_interface_impl.cpp
@@ -118,6 +119,14 @@ if(BUILD_TESTING)
118119
${rcl_interfaces_TARGETS}
119120
rclcpp::rclcpp)
120121
endif()
122+
ament_add_gtest(test_lifecycle_async_transitions test/test_lifecycle_async_transitions.cpp TIMEOUT 120)
123+
if(TARGET test_lifecycle_async_transitions)
124+
target_link_libraries(test_lifecycle_async_transitions
125+
${PROJECT_NAME}
126+
mimick
127+
${rcl_interfaces_TARGETS}
128+
rclcpp::rclcpp)
129+
endif()
121130
ament_add_gtest(test_service test/test_service.cpp TIMEOUT 120)
122131
if(TARGET test_service)
123132
target_link_libraries(test_service
Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
// Copyright 2023 Open Source Robotics Foundation, Inc.
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 RCLCPP_LIFECYCLE__CHANGE_STATE_HANDLER_HPP_
16+
#define RCLCPP_LIFECYCLE__CHANGE_STATE_HANDLER_HPP_
17+
18+
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
19+
20+
namespace rclcpp_lifecycle
21+
{
22+
/// The object passed to asynchronous change_state user transition functions
23+
class ChangeStateHandler
24+
{
25+
public:
26+
/// Continues the change state process handling proper callback order
27+
/** Used within the user defined transition callback to continue the change state process
28+
* similar to a service call response
29+
* Note this only allows sending a single response callback per object
30+
* and will not send further responses if called mutiple times on the object
31+
* \param[in] cb_return_code result of user defined transition callback
32+
* \return true if the response was successfully sent
33+
*/
34+
virtual bool send_callback_resp(
35+
node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code) = 0;
36+
37+
/// Updates the state machine based on the handling of a cancelled transition
38+
/**
39+
* \param[in] success true if the transition cancel request was successfully handled
40+
* \return true if the response was successfully sent to the state handler
41+
*/
42+
virtual bool handle_canceled(bool success) = 0;
43+
44+
/// Check to see if a send_callback_resp has been cancelled
45+
/**
46+
* @return true if response has been cancelled
47+
*/
48+
virtual bool is_canceling() const = 0;
49+
50+
// Check to see if the response has been sent
51+
/**
52+
* @return true if response has not been sent
53+
*/
54+
virtual bool is_executing() const = 0;
55+
56+
virtual ~ChangeStateHandler() = default;
57+
};
58+
} // namespace rclcpp_lifecycle
59+
60+
#endif // RCLCPP_LIFECYCLE__CHANGE_STATE_HANDLER_HPP_

rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp

Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,7 @@
9090
#include "rclcpp_lifecycle/state.hpp"
9191
#include "rclcpp_lifecycle/transition.hpp"
9292
#include "rclcpp_lifecycle/visibility_control.h"
93+
#include "rclcpp_lifecycle/change_state_handler.hpp"
9394

9495
namespace rclcpp_lifecycle
9596
{
@@ -1007,6 +1008,17 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
10071008
register_on_configure(
10081009
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
10091010

1011+
/// Register the configure async callback
1012+
/**
1013+
* This callback will be called when the transition to this state is triggered
1014+
* \param[in] fcn callback function to call
1015+
* \return always true
1016+
*/
1017+
RCLCPP_LIFECYCLE_PUBLIC
1018+
bool
1019+
register_async_on_configure(
1020+
std::function<void(const State &, std::shared_ptr<ChangeStateHandler>)> fcn);
1021+
10101022
/// Register the cleanup callback
10111023
/**
10121024
* This callback will be called when the transition to this state is triggered
@@ -1018,6 +1030,17 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
10181030
register_on_cleanup(
10191031
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
10201032

1033+
/// Register the cleanup async callback
1034+
/**
1035+
* This callback will be called when the transition to this state is triggered
1036+
* \param[in] fcn callback function to call
1037+
* \return always true
1038+
*/
1039+
RCLCPP_LIFECYCLE_PUBLIC
1040+
bool
1041+
register_async_on_cleanup(
1042+
std::function<void(const State &, std::shared_ptr<ChangeStateHandler>)> fcn);
1043+
10211044
/// Register the shutdown callback
10221045
/**
10231046
* This callback will be called when the transition to this state is triggered
@@ -1029,6 +1052,17 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
10291052
register_on_shutdown(
10301053
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
10311054

1055+
/// Register the shutdown async callback
1056+
/**
1057+
* This callback will be called when the transition to this state is triggered
1058+
* \param[in] fcn callback function to call
1059+
* \return always true
1060+
*/
1061+
RCLCPP_LIFECYCLE_PUBLIC
1062+
bool
1063+
register_async_on_shutdown(
1064+
std::function<void(const State &, std::shared_ptr<ChangeStateHandler>)> fcn);
1065+
10321066
/// Register the activate callback
10331067
/**
10341068
* This callback will be called when the transition to this state is triggered
@@ -1040,6 +1074,17 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
10401074
register_on_activate(
10411075
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
10421076

1077+
/// Register the activate async callback
1078+
/**
1079+
* This callback will be called when the transition to this state is triggered
1080+
* \param[in] fcn callback function to call
1081+
* \return always true
1082+
*/
1083+
RCLCPP_LIFECYCLE_PUBLIC
1084+
bool
1085+
register_async_on_activate(
1086+
std::function<void(const State &, std::shared_ptr<ChangeStateHandler>)> fcn);
1087+
10431088
/// Register the deactivate callback
10441089
/**
10451090
* This callback will be called when the transition to this state is triggered
@@ -1051,6 +1096,17 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
10511096
register_on_deactivate(
10521097
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
10531098

1099+
/// Register the deactivate async callback
1100+
/**
1101+
* This callback will be called when the transition to this state is triggered
1102+
* \param[in] fcn callback function to call
1103+
* \return always true
1104+
*/
1105+
RCLCPP_LIFECYCLE_PUBLIC
1106+
bool
1107+
register_async_on_deactivate(
1108+
std::function<void(const State &, std::shared_ptr<ChangeStateHandler>)> fcn);
1109+
10541110
/// Register the error callback
10551111
/**
10561112
* This callback will be called when the transition to this state is triggered
@@ -1062,6 +1118,17 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
10621118
register_on_error(
10631119
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
10641120

1121+
/// Register the error async callback
1122+
/**
1123+
* This callback will be called when the transition to this state is triggered
1124+
* \param[in] fcn callback function to call
1125+
* \return always true
1126+
*/
1127+
RCLCPP_LIFECYCLE_PUBLIC
1128+
bool
1129+
register_async_on_error(
1130+
std::function<void(const State &, std::shared_ptr<ChangeStateHandler>)> fcn);
1131+
10651132
RCLCPP_LIFECYCLE_PUBLIC
10661133
CallbackReturn
10671134
on_activate(const State & previous_state) override;
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
// Copyright 2023 Open Source Robotics Foundation, Inc.
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+
#include <memory>
16+
17+
#include "change_state_handler_impl.hpp"
18+
19+
namespace rclcpp_lifecycle
20+
{
21+
22+
ChangeStateHandlerImpl::ChangeStateHandlerImpl(
23+
const std::weak_ptr<LifecycleNodeStateManager> state_manager_hdl)
24+
: state_manager_hdl_(state_manager_hdl)
25+
{
26+
}
27+
28+
bool
29+
ChangeStateHandlerImpl::send_callback_resp(
30+
node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code)
31+
{
32+
if (!is_canceling() && is_executing()) {
33+
auto state_manager_hdl = state_manager_hdl_.lock();
34+
if (state_manager_hdl) {
35+
response_sent_.store(true);
36+
state_manager_hdl->process_callback_resp(cb_return_code);
37+
return true;
38+
}
39+
}
40+
return false;
41+
}
42+
43+
bool
44+
ChangeStateHandlerImpl::handle_canceled(bool success)
45+
{
46+
if (is_canceling() && is_executing()) {
47+
auto state_manager_hdl = state_manager_hdl_.lock();
48+
if (state_manager_hdl) {
49+
response_sent_.store(true);
50+
state_manager_hdl->user_handled_transition_cancel(success);
51+
return true;
52+
}
53+
}
54+
return false;
55+
}
56+
57+
bool
58+
ChangeStateHandlerImpl::is_canceling() const
59+
{
60+
return transition_is_cancelled_.load();
61+
}
62+
63+
bool
64+
ChangeStateHandlerImpl::is_executing() const
65+
{
66+
return !response_sent_.load();
67+
}
68+
69+
void
70+
ChangeStateHandlerImpl::cancel_transition()
71+
{
72+
transition_is_cancelled_.store(true);
73+
}
74+
75+
void
76+
ChangeStateHandlerImpl::invalidate()
77+
{
78+
response_sent_.store(true);
79+
}
80+
81+
} // namespace rclcpp_lifecycle
Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
// Copyright 2023 Open Source Robotics Foundation, Inc.
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 CHANGE_STATE_HANDLER_IMPL_HPP_
16+
#define CHANGE_STATE_HANDLER_IMPL_HPP_
17+
18+
#include <memory>
19+
#include <atomic>
20+
21+
#include "rclcpp_lifecycle/change_state_handler.hpp"
22+
#include "rclcpp/node_interfaces/node_base_interface.hpp"
23+
#include "lifecycle_node_state_manager.hpp"
24+
25+
namespace rclcpp_lifecycle
26+
{
27+
28+
class ChangeStateHandlerImpl : public ChangeStateHandler
29+
{
30+
public:
31+
explicit ChangeStateHandlerImpl(const std::weak_ptr<LifecycleNodeStateManager> state_manager_hdl);
32+
33+
bool send_callback_resp(
34+
node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code) override;
35+
36+
bool handle_canceled(bool success) override;
37+
38+
bool is_canceling() const override;
39+
40+
bool is_executing() const override;
41+
42+
/**
43+
* @brief Marks this transition as cancelled. It is up to the user to check if the transition
44+
* has been cancelled and attempt to handle it.
45+
*/
46+
void cancel_transition();
47+
48+
/**
49+
* @brief Invalidate the handler by setting the response_sent_ flag to true
50+
*/
51+
void invalidate();
52+
53+
private:
54+
std::weak_ptr<LifecycleNodeStateManager> state_manager_hdl_;
55+
std::atomic<bool> response_sent_{false};
56+
std::atomic<bool> transition_is_cancelled_{false};
57+
};
58+
} // namespace rclcpp_lifecycle
59+
#endif // CHANGE_STATE_HANDLER_IMPL_HPP_

0 commit comments

Comments
 (0)