Skip to content
Open
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,11 @@ if(BUILD_TESTING)
target_link_libraries(test_controller_tf_prefix
controller_interface
)

ament_add_gmock(test_test_utils test/test_test_utils.cpp)
target_link_libraries(test_test_utils
controller_interface
)
endif()

install(
Expand Down
165 changes: 165 additions & 0 deletions controller_interface/include/controller_interface/test_utils.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
// Copyright 2026 AIT - Austrian Institute of Technology GmbH
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef CONTROLLER_INTERFACE__TEST_UTILS_HPP_
#define CONTROLLER_INTERFACE__TEST_UTILS_HPP_

#include <memory>
#include <stdexcept>
#include <string>

#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
{
using lifecycle_msgs::msg::State;

/**
* @brief Triggers the controller's configure transition and checks success
*
* @note Intentionally calls controller->configure() instead of get_node()->configure() because
* ControllerInterfaceBase::configure() contains controller-specific configure logic and parameter
* handling before driving the lifecycle transition.
*
* @param controller The controller to test
* @return true if the controller successfully transitions to the expected state, false if it fails
* to
*
* @throws std::runtime_error if the controller transitions to an unexpected state
*/
template <typename T>
bool configure_succeeds(const std::unique_ptr<T> & controller)
{
auto state = controller->configure();

switch (state.id())
{
case State::PRIMARY_STATE_INACTIVE:
return true;
case State::PRIMARY_STATE_UNCONFIGURED:
return false;
default:
throw std::runtime_error(
"Unexpected controller state in configure_succeeds: " + std::to_string(state.id()));
}
}

/**
* @brief Triggers the controller's activate transition and checks success
*
* @param controller The controller to test
* @return true if the controller successfully transitions to the expected state, false if it fails
* to
*
* @throws std::runtime_error if the controller transitions to an unexpected state
*/
template <typename T>
bool activate_succeeds(const std::unique_ptr<T> & controller)
{
auto state = controller->get_node()->activate();

switch (state.id())
{
case State::PRIMARY_STATE_ACTIVE:
return true;
case State::PRIMARY_STATE_INACTIVE:
return false;
default:
// if transition returns error, it will go to on_error transition. Depending on its success,
// it will either land in unconfigured or finalized state
throw std::runtime_error(
"Unexpected controller state in activate_succeeds: " + std::to_string(state.id()));
}
}

/**
* @brief Triggers the controller's cleanup transition and checks success
*
* @param controller The controller to test
* @return true if the controller successfully transitions to the expected state, false if it fails
* to
*
* @throws std::runtime_error if the controller transitions to an unexpected state
*/
template <typename T>
bool deactivate_succeeds(const std::unique_ptr<T> & controller)
{
auto state = controller->get_node()->deactivate();

switch (state.id())
{
case State::PRIMARY_STATE_INACTIVE:
return true;
case State::PRIMARY_STATE_ACTIVE:

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Based on the design document found here https://design.ros2.org/articles/node_lifecycle.html
There is no explicit transition for onDeactivate[FAILURE], but since the test case you wrote for this one seems to PASS I assume the document is the outdated one and the behavior ACTIVE STATE -> Deactivate [Failed] -> ACTIVE STATE is expected.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

there are three return types of the transition callbacks:
https://github.com/ros2/rclcpp/blob/b6e9b4c9b48c48eae09ab79d7b2d4ef95e6c4653/rclcpp_lifecycle/include/rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp#L56-L61

As far as I understood it:

  • error: onError transition is called
  • failure: no transition is performed (staying in old state).

Here this means that after failure in on_deactivate, it will stay in active mode.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for sharing the link.
I guess it makes sense when the state transition fails (and no error is thrown), that the state will stay where it is.

return false;
default:
throw std::runtime_error(
"Unexpected controller state in deactivate_succeeds: " + std::to_string(state.id()));
}
}

/**
* @brief Triggers the controller's cleanup transition and checks success
*
* @param controller The controller to test
* @return true if the controller successfully transitions to the expected state, false if it fails
* to
*
* @throws std::runtime_error if the controller transitions to an unexpected state
*/
template <typename T>
bool cleanup_succeeds(const std::unique_ptr<T> & controller)
{
auto state = controller->get_node()->cleanup();

switch (state.id())
{
case State::PRIMARY_STATE_UNCONFIGURED:
return true;
case State::PRIMARY_STATE_INACTIVE:

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Based on the design document found here https://design.ros2.org/articles/node_lifecycle.html
There is no explicit transition for onCleanup[FAILURE], but since the test case you wrote for this one seems to PASS I assume the document is the outdated one and the behavior INACTIVE STATE -> Cleanup [Failed] -> INACTIVE STATE is expected.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same here, if transition fails it stays in inactive

return false;
default:
throw std::runtime_error(
"Unexpected controller state in cleanup_succeeds: " + std::to_string(state.id()));
}
}

/**
* @brief Triggers the controller's shutdown transition and checks success
*
* @param controller The controller to test
* @return true if the controller successfully transitions to the expected state, false if it fails
* to
*
* @throws std::runtime_error if the controller transitions to an unexpected state
*/
template <typename T>
bool shutdown_succeeds(const std::unique_ptr<T> & controller)
{
auto state = controller->get_node()->shutdown();

switch (state.id())
{
case State::PRIMARY_STATE_FINALIZED:
return true;
default:
// if transition returns error or failure, it will anyways end up in the finalized state

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this comment accurate? Based on the diagram included in https://design.ros2.org/articles/node_lifecycle.html
Suppose error is raised during onShutdown() then state will go to ErrorProcessing and further to Unconfigured or Finalized depending on the success/failure of onError.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this caused some headache, but this was the result of playing around with the tests.

The diagram also shows no [SUCCESS] condition for the shutdown.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you meant to say "The diagram also shows no [FAILURE] condition for the shutdown" ?

I think a more accurate comment for the default branch (at least based on the lifecycle diagram) would be
"if transition returns error, the state will end up in the Unconfigured or Finalized depending on the success/failure of onError"

throw std::runtime_error(
"Unexpected controller state in shutdown_succeeds: " + std::to_string(state.id()));
}
}

} // namespace controller_interface

#endif // CONTROLLER_INTERFACE__TEST_UTILS_HPP_
Loading
Loading