From 7843a26e4f0645b6d7a563562a7ff7edf6728fd9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 21 Aug 2024 10:58:31 +0200 Subject: [PATCH 1/6] Enable test_robot_model_parser test MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- urdf/CMakeLists.txt | 9 ++++++ urdf/test/test_robot_model_parser.cpp | 45 ++++++++++++++++----------- 2 files changed, 36 insertions(+), 18 deletions(-) diff --git a/urdf/CMakeLists.txt b/urdf/CMakeLists.txt index 43ed597f..b61126da 100644 --- a/urdf/CMakeLists.txt +++ b/urdf/CMakeLists.txt @@ -108,6 +108,15 @@ if(BUILD_TESTING) urdf ) add_dependencies(plugin_overhead "${mock_install_target}") + + add_definitions(-D_TEST_RESOURCES_DIR_PATH="${CMAKE_CURRENT_SOURCE_DIR}/test/") + + ament_add_gtest(test_robot_model_parser + test/test_robot_model_parser.cpp + ) + if(TARGET test_robot_model_parser) + target_link_libraries(test_robot_model_parser ${PROJECT_NAME} rcutils::rcutils) + endif() endif() # Export old-style CMake variables diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp index 19330ec2..075d6a90 100644 --- a/urdf/test/test_robot_model_parser.cpp +++ b/urdf/test/test_robot_model_parser.cpp @@ -41,10 +41,7 @@ #include "gtest/gtest.h" #include "urdf/model.h" -int g_argc; -char ** g_argv; - -class TestParser : public testing::Test +class TestParser : public testing::TestWithParam> { public: bool checkModel(urdf::Model & robot) @@ -109,11 +106,12 @@ class TestParser : public testing::Test size_t num_links; }; -TEST_F(TestParser, test) { - ASSERT_GE(g_argc, 3); - std::string folder = std::string(g_argv[1]) + "/test/"; +TEST_P(TestParser, test) { + std::vector const & input = GetParam(); + + std::string folder = _TEST_RESOURCES_DIR_PATH; fprintf(stderr, "Folder %s\n", folder.c_str()); - std::string file = std::string(g_argv[2]); + std::string file = std::string(input[0]); bool expect_success = (file.substr(0, 5) != "fail_"); urdf::Model robot; fprintf(stderr, "Parsing file %s, expecting %d\n", (folder + file).c_str(), expect_success); @@ -122,11 +120,10 @@ TEST_F(TestParser, test) { return; } - ASSERT_EQ(g_argc, 7); - std::string robot_name = std::string(g_argv[3]); - std::string root_name = std::string(g_argv[4]); - size_t expected_num_joints = atoi(g_argv[5]); - size_t expected_num_links = atoi(g_argv[6]); + std::string robot_name = std::string(input[1]); + std::string root_name = std::string(input[2]); + size_t expected_num_joints = atoi(input[3].c_str()); + size_t expected_num_links = atoi(input[4].c_str()); ASSERT_TRUE(robot.initFile(folder + file)); @@ -142,15 +139,27 @@ TEST_F(TestParser, test) { EXPECT_EQ(robot.links_.size(), expected_num_links); // test reading from parameter server - ASSERT_TRUE(robot.initParam("robot_description")); - ASSERT_FALSE(robot.initParam("robot_description_wim")); - SUCCEED(); + // ASSERT_TRUE(robot.initParam("robot_description")); + // ASSERT_FALSE(robot.initParam("robot_description_wim")); } +INSTANTIATE_TEST_CASE_P(GroupTestParser, TestParser, ::testing::Values( + std::vector({"test_robot.urdf", "r2d2", "dummy_link", "16", "17"}), + std::vector({"no_visual.urdf", "no_visual", "link1", "0", "1"}), + std::vector({"one_link.urdf", "one_link", "link1", "0", "1"}), + std::vector({"two_links_one_joint.urdf", "two_links_one_joint", "link1", "1", "2"}), + // Cases expected not to parse correctly only get filename information (path, urdf file) + std::vector({"fail_pr2_desc_bracket.urdf"}), + std::vector({"fail_three_links_one_joint.urdf"}), + std::vector({"fail_pr2_desc_double_joint.urdf"}), + std::vector({"fail_pr2_desc_loop.urdf"}), + std::vector({"fail_pr2_desc_no_filename_in_mesh.urdf"}), + std::vector({"fail_pr2_desc_no_joint2.urdf"}), + std::vector({"fail_pr2_desc_two_trees.urdf"}) +)); + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); - g_argc = argc; - g_argv = argv; return RUN_ALL_TESTS(); } From 8ea29a41181bc6ec927b35699f7d85515152f4b7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 21 Aug 2024 11:02:37 +0200 Subject: [PATCH 2/6] improvements MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- urdf/test/test_robot_model_parser.cpp | 20 ++++++++------------ 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp index 075d6a90..acb5f6ae 100644 --- a/urdf/test/test_robot_model_parser.cpp +++ b/urdf/test/test_robot_model_parser.cpp @@ -35,6 +35,7 @@ /* Author: Wim Meeussen */ #include +#include #include #include @@ -49,7 +50,7 @@ class TestParser : public testing::TestWithParam> // get root link urdf::LinkConstSharedPtr root_link = robot.getRoot(); if (!root_link) { - fprintf(stderr, "no root link %s\n", robot.getName().c_str()); + std::cerr << "no root link " << robot.getName() << std::endl; return false; } @@ -72,9 +73,8 @@ class TestParser : public testing::TestWithParam> bool traverse_tree(urdf::LinkConstSharedPtr link, int level = 0) { - fprintf( - stderr, "Traversing tree at level %d, link size %lu\n", - level, link->child_links.size()); + std::cerr << "Traversing tree at level " << level << " link size " + << link->child_links.size() << std::endl; level += 2; bool retval = true; for (std::vector::const_iterator child = link->child_links.begin(); @@ -88,13 +88,13 @@ class TestParser : public testing::TestWithParam> (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(roll, pitch, yaw); if (std::isnan(roll) || std::isnan(pitch) || std::isnan(yaw)) { - fprintf(stderr, "getRPY() returned nan!\n"); + std::cerr << "getRPY() returned nan!" << std::endl; return false; } // recurse down the tree retval &= this->traverse_tree(*child, level); } else { - fprintf(stderr, "root link: %s has a null child!\n", link->name.c_str()); + std::cerr << "root link: " << link->name << "has a null child!" << std::endl; return false; } } @@ -110,11 +110,11 @@ TEST_P(TestParser, test) { std::vector const & input = GetParam(); std::string folder = _TEST_RESOURCES_DIR_PATH; - fprintf(stderr, "Folder %s\n", folder.c_str()); + std::cerr << "Folder " << folder << std::endl; std::string file = std::string(input[0]); bool expect_success = (file.substr(0, 5) != "fail_"); urdf::Model robot; - fprintf(stderr, "Parsing file %s, expecting %d\n", (folder + file).c_str(), expect_success); + std::cerr << "Parsing file " << (folder + file) << ", expecting " << expect_success << std::endl; if (!expect_success) { ASSERT_FALSE(robot.initFile(folder + file)); return; @@ -137,10 +137,6 @@ TEST_P(TestParser, test) { EXPECT_EQ(num_links, expected_num_links); EXPECT_EQ(robot.joints_.size(), expected_num_joints); EXPECT_EQ(robot.links_.size(), expected_num_links); - - // test reading from parameter server - // ASSERT_TRUE(robot.initParam("robot_description")); - // ASSERT_FALSE(robot.initParam("robot_description_wim")); } INSTANTIATE_TEST_CASE_P(GroupTestParser, TestParser, ::testing::Values( From 661066e36892836156a00f3537d4db78c1eccabd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 21 Aug 2024 11:05:50 +0200 Subject: [PATCH 3/6] file not required anymore MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- urdf/test/test_robot_model_parser.launch | 19 ------------------- 1 file changed, 19 deletions(-) delete mode 100644 urdf/test/test_robot_model_parser.launch diff --git a/urdf/test/test_robot_model_parser.launch b/urdf/test/test_robot_model_parser.launch deleted file mode 100644 index 9953b55a..00000000 --- a/urdf/test/test_robot_model_parser.launch +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - From 66851c956f50568365436482041bbb21a9ff6850 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 21 Aug 2024 11:16:44 +0200 Subject: [PATCH 4/6] Added commom linters MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- urdf/CMakeLists.txt | 14 +-- urdf/include/urdf/model.h | 112 +++++++---------------- urdf/include/urdf/model.hpp | 84 +++++++++++++++++ urdf/include/urdf/visibility_control.hpp | 61 ++++++------ urdf/src/model.cpp | 63 ++++++------- urdf/src/rosconsole_bridge.cpp | 61 ++++++------ urdf/src/urdf_plugin.cpp | 61 ++++++------ urdf/test/benchmark_plugin_overhead.cpp | 64 ++++++------- urdf/test/test_robot_model_parser.cpp | 63 ++++++------- urdf/test/urdfdom_compatibility.cpp | 64 ++++++------- 10 files changed, 320 insertions(+), 327 deletions(-) create mode 100644 urdf/include/urdf/model.hpp diff --git a/urdf/CMakeLists.txt b/urdf/CMakeLists.txt index b61126da..3806fa7b 100644 --- a/urdf/CMakeLists.txt +++ b/urdf/CMakeLists.txt @@ -79,18 +79,8 @@ install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME}) if(BUILD_TESTING) - find_package(ament_cmake_cppcheck REQUIRED) - find_package(ament_cmake_cpplint REQUIRED) - find_package(ament_cmake_google_benchmark REQUIRED) - find_package(ament_cmake_lint_cmake REQUIRED) - find_package(ament_cmake_uncrustify REQUIRED) - # This forces cppcheck to consider all files in this project to be C++, - # including the headers which end with .h, which cppcheck would normally - # consider to be C instead. - ament_cppcheck(LANGUAGE "c++") - ament_cpplint() - ament_lint_cmake() - ament_uncrustify(LANGUAGE "C++") + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() pluginlib_enable_plugin_testing( CMAKE_TARGET_VAR mock_install_target diff --git a/urdf/include/urdf/model.h b/urdf/include/urdf/model.h index 23f6dd19..6c59a82e 100644 --- a/urdf/include/urdf/model.h +++ b/urdf/include/urdf/model.h @@ -1,89 +1,41 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2008, Willow Garage, Inc. -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2008, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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. /* Author: Wim Meeussen */ #ifndef URDF__MODEL_H_ #define URDF__MODEL_H_ -#include -#include +#warning \ + This header is obsolete, please include \ + urdf/model.hpp instead -#include "urdf_model/model.h" - -#include "urdf/urdfdom_compatibility.h" -#include "urdf/visibility_control.hpp" - -namespace urdf -{ - -// PIMPL Forward Declaration -class ModelImplementation; - -/// \brief Populates itself based on a robot descripton -/// -/// This class uses `urdf_parser_plugin` to parse the given robot description. -/// The chosen plugin is the one that reports the most confident score. -/// There is no way to override this choice except by uninstalling undesirable -/// parser plugins. -class Model : public ModelInterface -{ -public: - URDF_EXPORT - Model(); - - URDF_EXPORT - ~Model(); - - URDF_EXPORT Model(const Model & other); - URDF_EXPORT Model & operator=(const Model & other); - URDF_EXPORT Model(Model && other) noexcept; - URDF_EXPORT Model & operator=(Model && other)noexcept; - - /// \brief Load Model given a filename - URDF_EXPORT bool initFile(const std::string & filename); - - /// \brief Load Model from a XML-string - URDF_EXPORT bool initString(const std::string & xmlstring); - -private: - std::unique_ptr impl_; -}; - -// shared_ptr declarations moved to urdf/urdfdom_compatibility.h to allow for -// std::shared_ptrs in latest version - -} // namespace urdf +#include #endif // URDF__MODEL_H_ diff --git a/urdf/include/urdf/model.hpp b/urdf/include/urdf/model.hpp new file mode 100644 index 00000000..061a6557 --- /dev/null +++ b/urdf/include/urdf/model.hpp @@ -0,0 +1,84 @@ +// Copyright (c) 2008, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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. + +/* Author: Wim Meeussen */ + +#ifndef URDF__MODEL_HPP_ +#define URDF__MODEL_HPP_ + +#include +#include + +#include "urdf_model/model.h" + +#include "urdf/urdfdom_compatibility.h" +#include "urdf/visibility_control.hpp" + +namespace urdf +{ + +// PIMPL Forward Declaration +class ModelImplementation; + +/// \brief Populates itself based on a robot descripton +/// +/// This class uses `urdf_parser_plugin` to parse the given robot description. +/// The chosen plugin is the one that reports the most confident score. +/// There is no way to override this choice except by uninstalling undesirable +/// parser plugins. +class Model : public ModelInterface +{ +public: + URDF_EXPORT + Model(); + + URDF_EXPORT + ~Model(); + + URDF_EXPORT Model(const Model & other); + URDF_EXPORT Model & operator=(const Model & other); + URDF_EXPORT Model(Model && other) noexcept; + URDF_EXPORT Model & operator=(Model && other)noexcept; + + /// \brief Load Model given a filename + URDF_EXPORT bool initFile(const std::string & filename); + + /// \brief Load Model from a XML-string + URDF_EXPORT bool initString(const std::string & xmlstring); + +private: + std::unique_ptr impl_; +}; + +// shared_ptr declarations moved to urdf/urdfdom_compatibility.h to allow for +// std::shared_ptrs in latest version + +} // namespace urdf + +#endif // URDF__MODEL_HPP_ diff --git a/urdf/include/urdf/visibility_control.hpp b/urdf/include/urdf/visibility_control.hpp index 3b5925b7..f87412ec 100644 --- a/urdf/include/urdf/visibility_control.hpp +++ b/urdf/include/urdf/visibility_control.hpp @@ -1,36 +1,31 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2017, Open Source Robotics Foundation, Inc. -* All rights reserved. -* -* 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 copyright holder 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. -*********************************************************************/ +// Copyright (c) 2017, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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. /* This header must be included by all urdf headers which declare symbols * which are defined in the urdf library. When not building the urdf diff --git a/urdf/src/model.cpp b/urdf/src/model.cpp index a99b2ee3..3b67708e 100644 --- a/urdf/src/model.cpp +++ b/urdf/src/model.cpp @@ -1,40 +1,35 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2008, Willow Garage, Inc. -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2008, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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. /* Author: Wim Meeussen */ -#include "urdf/model.h" +#include "urdf/model.hpp" #include #include diff --git a/urdf/src/rosconsole_bridge.cpp b/urdf/src/rosconsole_bridge.cpp index d09daf93..f4b8a924 100644 --- a/urdf/src/rosconsole_bridge.cpp +++ b/urdf/src/rosconsole_bridge.cpp @@ -1,36 +1,31 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2011, Willow Garage, Inc. -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2011, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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 diff --git a/urdf/src/urdf_plugin.cpp b/urdf/src/urdf_plugin.cpp index 3c2f389b..7d682950 100644 --- a/urdf/src/urdf_plugin.cpp +++ b/urdf/src/urdf_plugin.cpp @@ -1,36 +1,31 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2020, Open Source Robotics Foundation, Inc. -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2020, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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 diff --git a/urdf/test/benchmark_plugin_overhead.cpp b/urdf/test/benchmark_plugin_overhead.cpp index d7c34f85..faeb6f88 100644 --- a/urdf/test/benchmark_plugin_overhead.cpp +++ b/urdf/test/benchmark_plugin_overhead.cpp @@ -1,43 +1,39 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2020, Willow Garage, Inc. -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2020, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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 #include -#include "urdf/model.h" +#include "urdf/model.hpp" const char test_xml[] = "" diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp index acb5f6ae..f7d80a8a 100644 --- a/urdf/test/test_robot_model_parser.cpp +++ b/urdf/test/test_robot_model_parser.cpp @@ -1,36 +1,31 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2008, Willow Garage, Inc. -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2008, Willow Garage, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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. /* Author: Wim Meeussen */ @@ -40,7 +35,7 @@ #include #include "gtest/gtest.h" -#include "urdf/model.h" +#include "urdf/model.hpp" class TestParser : public testing::TestWithParam> { diff --git a/urdf/test/urdfdom_compatibility.cpp b/urdf/test/urdfdom_compatibility.cpp index 43ba2a89..bb539636 100644 --- a/urdf/test/urdfdom_compatibility.cpp +++ b/urdf/test/urdfdom_compatibility.cpp @@ -1,42 +1,38 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2017 Open Source Robotics Foundation -* All rights reserved. -* -* 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. -*********************************************************************/ +// Copyright (c) 2017, Open Source Robotics Foundation, Inc. +// All rights reserved. +// +// 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 copyright holder 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 HOLDER 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 -#include "urdf/model.h" +#include "urdf/model.hpp" TEST(UrdfCompatibility, UpcastSharedPtr) { From 8cd9eaa3564a8fc3ae2018c23328788cd29b6709 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 21 Aug 2024 11:29:41 +0200 Subject: [PATCH 5/6] deprecation parser.h header MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- urdf/src/model.cpp | 2 +- urdf/src/urdf_plugin.cpp | 3 +- .../include/urdf_parser_plugin/parser.h | 38 ++-------- .../include/urdf_parser_plugin/parser.hpp | 70 +++++++++++++++++++ 4 files changed, 77 insertions(+), 36 deletions(-) create mode 100644 urdf_parser_plugin/include/urdf_parser_plugin/parser.hpp diff --git a/urdf/src/model.cpp b/urdf/src/model.cpp index 3b67708e..cb43c7e7 100644 --- a/urdf/src/model.cpp +++ b/urdf/src/model.cpp @@ -39,7 +39,7 @@ #include #include -#include "urdf_parser_plugin/parser.h" +#include "urdf_parser_plugin/parser.hpp" #include "pluginlib/class_loader.hpp" // Windows has preprocessor defines for "max", which conflicts with diff --git a/urdf/src/urdf_plugin.cpp b/urdf/src/urdf_plugin.cpp index 7d682950..3b951373 100644 --- a/urdf/src/urdf_plugin.cpp +++ b/urdf/src/urdf_plugin.cpp @@ -29,10 +29,11 @@ #include #include -#include #include +#include + namespace urdf { class URDFXMLParser final : public urdf::URDFParser diff --git a/urdf_parser_plugin/include/urdf_parser_plugin/parser.h b/urdf_parser_plugin/include/urdf_parser_plugin/parser.h index f7b8d2db..2d9922d2 100644 --- a/urdf_parser_plugin/include/urdf_parser_plugin/parser.h +++ b/urdf_parser_plugin/include/urdf_parser_plugin/parser.h @@ -31,40 +31,10 @@ #ifndef URDF_PARSER_PLUGIN__PARSER_H_ #define URDF_PARSER_PLUGIN__PARSER_H_ -#include +#warning \ + This header is obsolete, please include \ + urdf_parser_plugin/parser.hpp instead -#include "urdf_world/types.h" - -namespace urdf -{ - -/** \brief Base class for URDF parsers */ -class URDFParser -{ -public: - URDFParser() - { - } - virtual ~URDFParser() - { - } - - /// \brief Load Model from string - /// \return nullptr and write to stderr if the given string is invalid - virtual urdf::ModelInterfaceSharedPtr parse(const std::string & data) = 0; - - /// \brief Indicate if data is meant to be parsed by this parser - /// \return The position in the string that the plugin became confident the - /// data is intended to be parsed by it. - /// For example, the plugin parsing COLLADA files might return the - /// position in the string that the '' xml tag was found. - /// Smaller values are interpretted as more confidence, and the - /// plugin with the smallest value is used to parse the data. - /// If a plugin believes data is not meant for it, then it should - /// return a value greater than or equal to data.size(). - virtual size_t might_handle(const std::string & data) = 0; -}; - -} // namespace urdf +#include #endif // URDF_PARSER_PLUGIN__PARSER_H_ diff --git a/urdf_parser_plugin/include/urdf_parser_plugin/parser.hpp b/urdf_parser_plugin/include/urdf_parser_plugin/parser.hpp new file mode 100644 index 00000000..d23e761c --- /dev/null +++ b/urdf_parser_plugin/include/urdf_parser_plugin/parser.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2013, Willow Garage, Inc. +// +// 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 HOLDER 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. + +/* Author: Ioan Sucan */ + +#ifndef URDF_PARSER_PLUGIN__PARSER_HPP_ +#define URDF_PARSER_PLUGIN__PARSER_HPP_ + +#include + +#include "urdf_world/types.h" + +namespace urdf +{ + +/** \brief Base class for URDF parsers */ +class URDFParser +{ +public: + URDFParser() + { + } + virtual ~URDFParser() + { + } + + /// \brief Load Model from string + /// \return nullptr and write to stderr if the given string is invalid + virtual urdf::ModelInterfaceSharedPtr parse(const std::string & data) = 0; + + /// \brief Indicate if data is meant to be parsed by this parser + /// \return The position in the string that the plugin became confident the + /// data is intended to be parsed by it. + /// For example, the plugin parsing COLLADA files might return the + /// position in the string that the '' xml tag was found. + /// Smaller values are interpretted as more confidence, and the + /// plugin with the smallest value is used to parse the data. + /// If a plugin believes data is not meant for it, then it should + /// return a value greater than or equal to data.size(). + virtual size_t might_handle(const std::string & data) = 0; +}; + +} // namespace urdf + +#endif // URDF_PARSER_PLUGIN__PARSER_HPP_ From 26da21715e7022a34235c47e279873625e81b7f6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 23 Aug 2024 16:38:58 +0200 Subject: [PATCH 6/6] fixed windows cppcheck MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- .vscode/settings.json | 58 +++++++++++++++++++++++++++++++++++++++++++ urdf/CMakeLists.txt | 1 + 2 files changed, 59 insertions(+) create mode 100644 .vscode/settings.json diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..db0fc0b5 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,58 @@ +{ + "files.associations": { + "cctype": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "cwchar": "cpp", + "array": "cpp", + "atomic": "cpp", + "bit": "cpp", + "*.tcc": "cpp", + "compare": "cpp", + "complex": "cpp", + "concepts": "cpp", + "cstdint": "cpp", + "map": "cpp", + "set": "cpp", + "string": "cpp", + "unordered_map": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "optional": "cpp", + "random": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "initializer_list": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "new": "cpp", + "ostream": "cpp", + "ranges": "cpp", + "span": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "cinttypes": "cpp", + "typeinfo": "cpp", + "ctime": "cpp", + "cwctype": "cpp", + "numbers": "cpp" + } +} diff --git a/urdf/CMakeLists.txt b/urdf/CMakeLists.txt index 3806fa7b..3dbe205f 100644 --- a/urdf/CMakeLists.txt +++ b/urdf/CMakeLists.txt @@ -80,6 +80,7 @@ install(DIRECTORY include/ if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) + set(ament_cmake_cppcheck_LANGUAGE "c++") ament_lint_auto_find_test_dependencies() pluginlib_enable_plugin_testing(