ros2_control - rolling
Loading...
Searching...
No Matches
test_utils.hpp
1// Copyright 2026 AIT - Austrian Institute of Technology GmbH
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 CONTROLLER_INTERFACE__TEST_UTILS_HPP_
16#define CONTROLLER_INTERFACE__TEST_UTILS_HPP_
17
18#include <memory>
19#include <stdexcept>
20#include <string>
21
22#include "lifecycle_msgs/msg/state.hpp"
23
24namespace controller_interface
25{
26using lifecycle_msgs::msg::State;
27
41template <typename T>
42bool configure_succeeds(const std::unique_ptr<T> & controller)
43{
44 auto state = controller->configure();
45
46 switch (state.id())
47 {
48 case State::PRIMARY_STATE_INACTIVE:
49 return true;
50 case State::PRIMARY_STATE_UNCONFIGURED:
51 return false;
52 default:
53 throw std::runtime_error(
54 "Unexpected controller state in configure_succeeds: " + std::to_string(state.id()));
55 }
56}
57
67template <typename T>
68bool activate_succeeds(const std::unique_ptr<T> & controller)
69{
70 auto state = controller->get_node()->activate();
71
72 switch (state.id())
73 {
74 case State::PRIMARY_STATE_ACTIVE:
75 return true;
76 case State::PRIMARY_STATE_INACTIVE:
77 return false;
78 default:
79 // if transition returns error, it will go to on_error transition. Depending on its success,
80 // it will either land in unconfigured or finalized state
81 throw std::runtime_error(
82 "Unexpected controller state in activate_succeeds: " + std::to_string(state.id()));
83 }
84}
85
95template <typename T>
96bool deactivate_succeeds(const std::unique_ptr<T> & controller)
97{
98 auto state = controller->get_node()->deactivate();
99
100 switch (state.id())
101 {
102 case State::PRIMARY_STATE_INACTIVE:
103 return true;
104 case State::PRIMARY_STATE_ACTIVE:
105 return false;
106 default:
107 throw std::runtime_error(
108 "Unexpected controller state in deactivate_succeeds: " + std::to_string(state.id()));
109 }
110}
111
121template <typename T>
122bool cleanup_succeeds(const std::unique_ptr<T> & controller)
123{
124 auto state = controller->get_node()->cleanup();
125
126 switch (state.id())
127 {
128 case State::PRIMARY_STATE_UNCONFIGURED:
129 return true;
130 case State::PRIMARY_STATE_INACTIVE:
131 return false;
132 default:
133 throw std::runtime_error(
134 "Unexpected controller state in cleanup_succeeds: " + std::to_string(state.id()));
135 }
136}
137
146template <typename T>
147bool shutdown_succeeds(const std::unique_ptr<T> & controller)
148{
149 auto state = controller->get_node()->shutdown();
150
151 switch (state.id())
152 {
153 // if shutdown transition returns success or failure, it will anyways end up in the finalized
154 // state
155 // The observed behavior is not as described in
156 // https://design.ros2.org/articles/node_lifecycle.html
157 // See https://github.com/ros2/rclcpp/issues/1763 for more information
158 // if shutdown transition returns error, it will go to on_error transition:
159 // If on_error returns failure, it will end up in finalized state
160 case State::PRIMARY_STATE_FINALIZED:
161 return true;
162 default:
163 // if shutdowntransition returns error, it will go to on_error transition:
164 // If on_error returns success, it will end up in unconfigured state
165 throw std::runtime_error(
166 "Unexpected controller state in shutdown_succeeds: " + std::to_string(state.id()));
167 }
168}
169
170} // namespace controller_interface
171
172#endif // CONTROLLER_INTERFACE__TEST_UTILS_HPP_