Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 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 @@ -117,6 +117,11 @@ if(BUILD_TESTING)
hardware_interface::hardware_interface
${std_msgs_TARGETS}
)

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

install(
Expand Down
28 changes: 28 additions & 0 deletions controller_interface/include/controller_interface/helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,34 @@ inline bool interface_list_contains_interface_type(
interface_type_list.end();
}

/**
* @brief Resolve the TF prefix with normalized slashes
* @param prefix The TF prefix
* @param node_ns Node namespace to use as prefix if prefix is empty
* @return Prefix to be prepended
*/
inline std::string resolve_tf_prefix(const std::string & prefix, const std::string & node_ns)
{
if (prefix.empty())
{
return std::string{};
}

std::string nprefix = prefix == "~" ? node_ns : prefix;

// ensure trailing '/'
if (nprefix.back() != '/')
{
nprefix.push_back('/');
}
// remove leading '/'
if (nprefix.front() == '/')
{
nprefix.erase(0, 1);
}
return nprefix;
}

} // namespace controller_interface

#endif // CONTROLLER_INTERFACE__HELPERS_HPP_
42 changes: 42 additions & 0 deletions controller_interface/test/test_controller_tf_prefix.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright (c) 2025, ros2_control developers
//
// 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.

#include <gmock/gmock.h>

#include "controller_interface/helpers.hpp"
#include "test_controller_tf_prefix.hpp"

TEST_F(TestControllerTFPrefix, EmptyPrefixReturnsEmpty)
{
EXPECT_EQ(controller_interface::resolve_tf_prefix("", "/ns"), "");
}

TEST_F(TestControllerTFPrefix, TildePrefixUsesNamespace)
{
EXPECT_EQ(controller_interface::resolve_tf_prefix("~", "/ns"), "ns/");
EXPECT_EQ(controller_interface::resolve_tf_prefix("~", "/ns/"), "ns/");
}

TEST_F(TestControllerTFPrefix, ExplicitPrefixUsed)
{
EXPECT_EQ(controller_interface::resolve_tf_prefix("robot", "/ns"), "robot/");
}

TEST_F(TestControllerTFPrefix, NormalizePrefixSlashes)
{
EXPECT_EQ(controller_interface::resolve_tf_prefix("/robot1", "/ns"), "robot1/");
EXPECT_EQ(controller_interface::resolve_tf_prefix("robot2//", "/ns"), "robot2//");
EXPECT_EQ(controller_interface::resolve_tf_prefix("/robot3/", "/ns"), "robot3/");
EXPECT_EQ(controller_interface::resolve_tf_prefix("/", "/ns"), "");
}
34 changes: 34 additions & 0 deletions controller_interface/test/test_controller_tf_prefix.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
// Copyright (c) 2025, ros2_control developers
//
// 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 TEST_CONTROLLER_TF_PREFIX_HPP_
#define TEST_CONTROLLER_TF_PREFIX_HPP_

#include <gmock/gmock.h>
#include <gtest/gtest.h>

class TestControllerTFPrefix : public ::testing::Test
{
public:
void SetUp() override
{
// placeholder
}
void TearDown() override
{
// placeholder
}
};

#endif // TEST_CONTROLLER_TF_PREFIX_HPP_
Loading