From 14ddfc39ad89730d08320d97d7cc8e8c735732b4 Mon Sep 17 00:00:00 2001 From: kuralme Date: Fri, 24 Oct 2025 15:30:58 -0400 Subject: [PATCH 1/5] TF prefix helper added --- control_toolbox/CMakeLists.txt | 3 + .../include/control_toolbox/tf_utils.hpp | 83 +++++++++++++++++++ control_toolbox/test/tf_utils_tests.cpp | 76 +++++++++++++++++ 3 files changed, 162 insertions(+) create mode 100644 control_toolbox/include/control_toolbox/tf_utils.hpp create mode 100644 control_toolbox/test/tf_utils_tests.cpp diff --git a/control_toolbox/CMakeLists.txt b/control_toolbox/CMakeLists.txt index b7b5d028..7c468cf4 100644 --- a/control_toolbox/CMakeLists.txt +++ b/control_toolbox/CMakeLists.txt @@ -183,6 +183,9 @@ if(BUILD_TESTING) ament_add_gmock(pid_ros_publisher_tests test/pid_ros_publisher_tests.cpp) target_link_libraries(pid_ros_publisher_tests control_toolbox rclcpp_lifecycle::rclcpp_lifecycle) + ament_add_gmock(tf_utils_tests test/tf_utils_tests.cpp) + target_link_libraries(tf_utils_tests control_toolbox) + ## Control Filters ### Gravity Compensation add_rostest_with_parameters_gmock(test_gravity_compensation test/control_filters/test_gravity_compensation.cpp diff --git a/control_toolbox/include/control_toolbox/tf_utils.hpp b/control_toolbox/include/control_toolbox/tf_utils.hpp new file mode 100644 index 00000000..7e144699 --- /dev/null +++ b/control_toolbox/include/control_toolbox/tf_utils.hpp @@ -0,0 +1,83 @@ +// Copyright (c) 2008, Willow Garage, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of the Willow Garage nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#ifndef CONTROL_TOOLBOX__TF_UTILS_HPP_ +#define CONTROL_TOOLBOX__TF_UTILS_HPP_ + +#include + +#include + +namespace control_toolbox +{ +/** +* @brief Apply a TF prefix to a given frame. +* @param tf_prefix_enabled Whether to apply the TF prefix +* @param prefix TF prefix +* @param frame Frame name +* @param node_ns Node namespace to use as prefix if prefix is empty +* @return The prefixed frame name if prefix is not empty, otherwise the original frame name +*/ +inline std::string applyTFPrefix( + bool tf_prefix_enabled, std::string prefix, const std::string & node_ns, + const std::string & frame) +{ + if (!tf_prefix_enabled) + { + return frame; + } + + // fallback to node namespace if explicit prefix not set + if (prefix.empty()) + { + prefix = node_ns; + } + + // normalize: remove leading '/' and ensure trailing '/' + if (!prefix.empty()) + { + if (prefix.front() == '/') + { + prefix.erase(0, 1); + } + if (prefix.back() != '/') + { + prefix.push_back('/'); + } + } + + return prefix + frame; +} + +} // namespace control_toolbox + +#endif // CONTROL_TOOLBOX__TF_UTILS_HPP_ diff --git a/control_toolbox/test/tf_utils_tests.cpp b/control_toolbox/test/tf_utils_tests.cpp new file mode 100644 index 00000000..a95f2e3b --- /dev/null +++ b/control_toolbox/test/tf_utils_tests.cpp @@ -0,0 +1,76 @@ +// Copyright (c) 2008, Willow Garage, Inc. +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of the Willow Garage nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#include +#include "control_toolbox/tf_utils.hpp" + +TEST(ApplyTFPrefixTest, DisabledPrefix) +{ + EXPECT_EQ(control_toolbox::applyTFPrefix(false, "", "/ns", "base_link"), "base_link"); +} + +TEST(ApplyTFPrefixTest, EmptyExplicitUsesNamespace) +{ + EXPECT_EQ(control_toolbox::applyTFPrefix(true, "", "/my_ns", "odom"), "my_ns/odom"); +} + +TEST(ApplyTFPrefixTest, ExplicitPrefixUsed) +{ + EXPECT_EQ(control_toolbox::applyTFPrefix(true, "robot1", "/ns", "base"), "robot1/base"); +} + +TEST(ApplyTFPrefixTest, LeadingSlashRemoved) +{ + EXPECT_EQ(control_toolbox::applyTFPrefix(true, "/robot2", "/ns", "link"), "robot2/link"); +} + +TEST(ApplyTFPrefixTest, TrailingSlashAdded) +{ + EXPECT_EQ(control_toolbox::applyTFPrefix(true, "robot3", "/ns", "odom"), "robot3/odom"); +} + +TEST(ApplyTFPrefixTest, BothSlashesNormalized) +{ + EXPECT_EQ( + control_toolbox::applyTFPrefix(true, "/robot4/", "/ns", "base_link"), "robot4/base_link"); +} + +TEST(ApplyTFPrefixTest, NodeNamespaceWithSlash) +{ + EXPECT_EQ(control_toolbox::applyTFPrefix(true, "", "/robot_ns/", "odom"), "robot_ns/odom"); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From 1e397505f49fb669fa1e92c6ce7c283f8ab7d656 Mon Sep 17 00:00:00 2001 From: kuralme Date: Sat, 25 Oct 2025 06:47:57 -0400 Subject: [PATCH 2/5] copyright and function name style updated --- .../include/control_toolbox/tf_utils.hpp | 4 ++-- control_toolbox/test/tf_utils_tests.cpp | 16 ++++++++-------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/control_toolbox/include/control_toolbox/tf_utils.hpp b/control_toolbox/include/control_toolbox/tf_utils.hpp index 7e144699..6b0f2169 100644 --- a/control_toolbox/include/control_toolbox/tf_utils.hpp +++ b/control_toolbox/include/control_toolbox/tf_utils.hpp @@ -1,4 +1,4 @@ -// Copyright (c) 2008, Willow Garage, Inc. +// Copyright (c) 2025, ros2_control developers // All rights reserved. // // Software License Agreement (BSD License 2.0) @@ -47,7 +47,7 @@ namespace control_toolbox * @param node_ns Node namespace to use as prefix if prefix is empty * @return The prefixed frame name if prefix is not empty, otherwise the original frame name */ -inline std::string applyTFPrefix( +inline std::string apply_tf_prefix( bool tf_prefix_enabled, std::string prefix, const std::string & node_ns, const std::string & frame) { diff --git a/control_toolbox/test/tf_utils_tests.cpp b/control_toolbox/test/tf_utils_tests.cpp index a95f2e3b..3afc5674 100644 --- a/control_toolbox/test/tf_utils_tests.cpp +++ b/control_toolbox/test/tf_utils_tests.cpp @@ -1,4 +1,4 @@ -// Copyright (c) 2008, Willow Garage, Inc. +// Copyright (c) 2025, ros2_control developers // All rights reserved. // // Software License Agreement (BSD License 2.0) @@ -35,38 +35,38 @@ TEST(ApplyTFPrefixTest, DisabledPrefix) { - EXPECT_EQ(control_toolbox::applyTFPrefix(false, "", "/ns", "base_link"), "base_link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix(false, "", "/ns", "base_link"), "base_link"); } TEST(ApplyTFPrefixTest, EmptyExplicitUsesNamespace) { - EXPECT_EQ(control_toolbox::applyTFPrefix(true, "", "/my_ns", "odom"), "my_ns/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "", "/my_ns", "odom"), "my_ns/odom"); } TEST(ApplyTFPrefixTest, ExplicitPrefixUsed) { - EXPECT_EQ(control_toolbox::applyTFPrefix(true, "robot1", "/ns", "base"), "robot1/base"); + EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "robot1", "/ns", "base"), "robot1/base"); } TEST(ApplyTFPrefixTest, LeadingSlashRemoved) { - EXPECT_EQ(control_toolbox::applyTFPrefix(true, "/robot2", "/ns", "link"), "robot2/link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "/robot2", "/ns", "link"), "robot2/link"); } TEST(ApplyTFPrefixTest, TrailingSlashAdded) { - EXPECT_EQ(control_toolbox::applyTFPrefix(true, "robot3", "/ns", "odom"), "robot3/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "robot3", "/ns", "odom"), "robot3/odom"); } TEST(ApplyTFPrefixTest, BothSlashesNormalized) { EXPECT_EQ( - control_toolbox::applyTFPrefix(true, "/robot4/", "/ns", "base_link"), "robot4/base_link"); + control_toolbox::apply_tf_prefix(true, "/robot4/", "/ns", "base_link"), "robot4/base_link"); } TEST(ApplyTFPrefixTest, NodeNamespaceWithSlash) { - EXPECT_EQ(control_toolbox::applyTFPrefix(true, "", "/robot_ns/", "odom"), "robot_ns/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "", "/robot_ns/", "odom"), "robot_ns/odom"); } int main(int argc, char ** argv) From ea74c8fd15f06ed40274395f4f42f4836fb9b620 Mon Sep 17 00:00:00 2001 From: kuralme Date: Wed, 29 Oct 2025 09:53:39 -0400 Subject: [PATCH 3/5] removed prefix enabler input --- .../include/control_toolbox/tf_utils.hpp | 32 ++++++------------- control_toolbox/test/tf_utils_tests.cpp | 18 ++++------- 2 files changed, 16 insertions(+), 34 deletions(-) diff --git a/control_toolbox/include/control_toolbox/tf_utils.hpp b/control_toolbox/include/control_toolbox/tf_utils.hpp index 6b0f2169..5994386a 100644 --- a/control_toolbox/include/control_toolbox/tf_utils.hpp +++ b/control_toolbox/include/control_toolbox/tf_utils.hpp @@ -40,42 +40,30 @@ namespace control_toolbox { /** -* @brief Apply a TF prefix to a given frame. -* @param tf_prefix_enabled Whether to apply the TF prefix +* @brief Apply TF prefix to given frame * @param prefix TF prefix -* @param frame Frame name * @param node_ns Node namespace to use as prefix if prefix is empty +* @param frame Frame name * @return The prefixed frame name if prefix is not empty, otherwise the original frame name */ inline std::string apply_tf_prefix( - bool tf_prefix_enabled, std::string prefix, const std::string & node_ns, - const std::string & frame) + const std::string & prefix, const std::string & node_ns, const std::string & frame) { - if (!tf_prefix_enabled) - { - return frame; - } - - // fallback to node namespace if explicit prefix not set - if (prefix.empty()) - { - prefix = node_ns; - } + std::string nprefix = prefix.empty() ? node_ns : prefix; // normalize: remove leading '/' and ensure trailing '/' - if (!prefix.empty()) + if (!nprefix.empty()) { - if (prefix.front() == '/') + if (nprefix.front() == '/') { - prefix.erase(0, 1); + nprefix.erase(0, 1); } - if (prefix.back() != '/') + if (nprefix.back() != '/') { - prefix.push_back('/'); + nprefix.push_back('/'); } } - - return prefix + frame; + return nprefix + frame; } } // namespace control_toolbox diff --git a/control_toolbox/test/tf_utils_tests.cpp b/control_toolbox/test/tf_utils_tests.cpp index 3afc5674..bc4215ea 100644 --- a/control_toolbox/test/tf_utils_tests.cpp +++ b/control_toolbox/test/tf_utils_tests.cpp @@ -33,40 +33,34 @@ #include #include "control_toolbox/tf_utils.hpp" -TEST(ApplyTFPrefixTest, DisabledPrefix) -{ - EXPECT_EQ(control_toolbox::apply_tf_prefix(false, "", "/ns", "base_link"), "base_link"); -} - TEST(ApplyTFPrefixTest, EmptyExplicitUsesNamespace) { - EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "", "/my_ns", "odom"), "my_ns/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("", "/my_ns", "odom"), "my_ns/odom"); } TEST(ApplyTFPrefixTest, ExplicitPrefixUsed) { - EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "robot1", "/ns", "base"), "robot1/base"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("robot1", "/ns", "base"), "robot1/base"); } TEST(ApplyTFPrefixTest, LeadingSlashRemoved) { - EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "/robot2", "/ns", "link"), "robot2/link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot2", "/ns", "link"), "robot2/link"); } TEST(ApplyTFPrefixTest, TrailingSlashAdded) { - EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "robot3", "/ns", "odom"), "robot3/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("robot3", "/ns", "odom"), "robot3/odom"); } TEST(ApplyTFPrefixTest, BothSlashesNormalized) { - EXPECT_EQ( - control_toolbox::apply_tf_prefix(true, "/robot4/", "/ns", "base_link"), "robot4/base_link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot4/", "/ns", "base_link"), "robot4/base_link"); } TEST(ApplyTFPrefixTest, NodeNamespaceWithSlash) { - EXPECT_EQ(control_toolbox::apply_tf_prefix(true, "", "/robot_ns/", "odom"), "robot_ns/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("", "/robot_ns/", "odom"), "robot_ns/odom"); } int main(int argc, char ** argv) From b2fe32bfe5309e79fe392b34d42a2299d4740656 Mon Sep 17 00:00:00 2001 From: kuralme Date: Wed, 29 Oct 2025 11:33:40 -0400 Subject: [PATCH 4/5] normalization logic reverted to original --- .../include/control_toolbox/tf_utils.hpp | 12 +++++---- control_toolbox/test/tf_utils_tests.cpp | 27 ++++++++++--------- 2 files changed, 22 insertions(+), 17 deletions(-) diff --git a/control_toolbox/include/control_toolbox/tf_utils.hpp b/control_toolbox/include/control_toolbox/tf_utils.hpp index 5994386a..b02aed46 100644 --- a/control_toolbox/include/control_toolbox/tf_utils.hpp +++ b/control_toolbox/include/control_toolbox/tf_utils.hpp @@ -51,17 +51,19 @@ inline std::string apply_tf_prefix( { std::string nprefix = prefix.empty() ? node_ns : prefix; - // normalize: remove leading '/' and ensure trailing '/' + // Normalize the prefix if (!nprefix.empty()) { - if (nprefix.front() == '/') - { - nprefix.erase(0, 1); - } + // ensure trailing '/' if (nprefix.back() != '/') { nprefix.push_back('/'); } + // remove leading '/' + if (nprefix.front() == '/') + { + nprefix.erase(0, 1); + } } return nprefix + frame; } diff --git a/control_toolbox/test/tf_utils_tests.cpp b/control_toolbox/test/tf_utils_tests.cpp index bc4215ea..9e501c29 100644 --- a/control_toolbox/test/tf_utils_tests.cpp +++ b/control_toolbox/test/tf_utils_tests.cpp @@ -33,34 +33,37 @@ #include #include "control_toolbox/tf_utils.hpp" -TEST(ApplyTFPrefixTest, EmptyExplicitUsesNamespace) +TEST(ApplyTFPrefixTest, UsesNamespaceWhenPrefixEmpty) { - EXPECT_EQ(control_toolbox::apply_tf_prefix("", "/my_ns", "odom"), "my_ns/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("", "/ns", "odom"), "ns/odom"); } -TEST(ApplyTFPrefixTest, ExplicitPrefixUsed) +TEST(ApplyTFPrefixTest, UsesExplicitPrefix) { - EXPECT_EQ(control_toolbox::apply_tf_prefix("robot1", "/ns", "base"), "robot1/base"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("robot", "/ns", "base"), "robot/base"); } -TEST(ApplyTFPrefixTest, LeadingSlashRemoved) +TEST(ApplyTFPrefixTest, NormalizesPrefixSlashes) { - EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot2", "/ns", "link"), "robot2/link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot1", "/ns", "link"), "robot1/link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("robot2//", "/ns", "odom"), "robot2//odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot3/", "/ns", "base_link"), "robot3/base_link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("/", "/ns", "odom"), "odom"); } -TEST(ApplyTFPrefixTest, TrailingSlashAdded) +TEST(ApplyTFPrefixTest, EmptyPrefixAndNamespace) { - EXPECT_EQ(control_toolbox::apply_tf_prefix("robot3", "/ns", "odom"), "robot3/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("", "", "odom"), "odom"); } -TEST(ApplyTFPrefixTest, BothSlashesNormalized) +TEST(ApplyTFPrefixTest, FrameHasLeadingSlash) { - EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot4/", "/ns", "base_link"), "robot4/base_link"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("robot", "/ns", "/odom"), "robot//odom"); } -TEST(ApplyTFPrefixTest, NodeNamespaceWithSlash) +TEST(ApplyTFPrefixTest, ComplexPrefixAndNamespace) { - EXPECT_EQ(control_toolbox::apply_tf_prefix("", "/robot_ns/", "odom"), "robot_ns/odom"); + EXPECT_EQ(control_toolbox::apply_tf_prefix("/robot/", "/my_ns/", "odom"), "robot/odom"); } int main(int argc, char ** argv) From 156e2414eaf1719407ab73b56a398915592623fe Mon Sep 17 00:00:00 2001 From: kuralme Date: Mon, 3 Nov 2025 08:52:53 -0500 Subject: [PATCH 5/5] licence updated --- .../include/control_toolbox/tf_utils.hpp | 36 +++++-------------- control_toolbox/test/tf_utils_tests.cpp | 36 +++++-------------- 2 files changed, 18 insertions(+), 54 deletions(-) diff --git a/control_toolbox/include/control_toolbox/tf_utils.hpp b/control_toolbox/include/control_toolbox/tf_utils.hpp index b02aed46..0fbc80af 100644 --- a/control_toolbox/include/control_toolbox/tf_utils.hpp +++ b/control_toolbox/include/control_toolbox/tf_utils.hpp @@ -1,34 +1,16 @@ // Copyright (c) 2025, ros2_control developers -// All rights reserved. // -// Software License Agreement (BSD License 2.0) +// 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 // -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions -// are met: +// http://www.apache.org/licenses/LICENSE-2.0 // -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above -// copyright notice, this list of conditions and the following -// disclaimer in the documentation and/or other materials provided -// with the distribution. -// * Neither the name of the Willow Garage nor the names of its -// contributors may be used to endorse or promote products derived -// from this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. +// 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 CONTROL_TOOLBOX__TF_UTILS_HPP_ #define CONTROL_TOOLBOX__TF_UTILS_HPP_ diff --git a/control_toolbox/test/tf_utils_tests.cpp b/control_toolbox/test/tf_utils_tests.cpp index 9e501c29..b9a67a98 100644 --- a/control_toolbox/test/tf_utils_tests.cpp +++ b/control_toolbox/test/tf_utils_tests.cpp @@ -1,34 +1,16 @@ // Copyright (c) 2025, ros2_control developers -// All rights reserved. // -// Software License Agreement (BSD License 2.0) +// 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 // -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions -// are met: +// http://www.apache.org/licenses/LICENSE-2.0 // -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above -// copyright notice, this list of conditions and the following -// disclaimer in the documentation and/or other materials provided -// with the distribution. -// * Neither the name of the Willow Garage nor the names of its -// contributors may be used to endorse or promote products derived -// from this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. +// 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 #include "control_toolbox/tf_utils.hpp"