diff --git a/rclcpp/include/rclcpp/any_executable.hpp b/rclcpp/include/rclcpp/any_executable.hpp index ed01d45bc1..5d4064f452 100644 --- a/rclcpp/include/rclcpp/any_executable.hpp +++ b/rclcpp/include/rclcpp/any_executable.hpp @@ -50,12 +50,6 @@ struct AnyExecutable std::shared_ptr data; }; -namespace executor -{ - -using AnyExecutable [[deprecated("use rclcpp::AnyExecutable instead")]] = AnyExecutable; - -} // namespace executor } // namespace rclcpp #endif // RCLCPP__ANY_EXECUTABLE_HPP_ diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index fe52d287bb..efa8352206 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -222,13 +222,6 @@ class CallbackGroup } }; -namespace callback_group -{ - -using CallbackGroupType [[deprecated("use rclcpp::CallbackGroupType instead")]] = CallbackGroupType; -using CallbackGroup [[deprecated("use rclcpp::CallbackGroup instead")]] = CallbackGroup; - -} // namespace callback_group } // namespace rclcpp #endif // RCLCPP__CALLBACK_GROUP_HPP_ diff --git a/rclcpp/include/rclcpp/contexts/default_context.hpp b/rclcpp/include/rclcpp/contexts/default_context.hpp index 0c2bbf8265..7c4ac63ef0 100644 --- a/rclcpp/include/rclcpp/contexts/default_context.hpp +++ b/rclcpp/include/rclcpp/contexts/default_context.hpp @@ -36,22 +36,6 @@ RCLCPP_PUBLIC DefaultContext::SharedPtr get_global_default_context(); -namespace default_context -{ - -using DefaultContext -[[deprecated("use rclcpp::contexts::DefaultContext instead")]] = DefaultContext; - -[[deprecated("use rclcpp::contexts::get_global_default_context() instead")]] -RCLCPP_PUBLIC -inline -DefaultContext::SharedPtr -get_global_default_context() -{ - return rclcpp::contexts::get_global_default_context(); -} - -} // namespace default_context } // namespace contexts } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 9321f679fc..bc4e167a1e 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -573,12 +573,6 @@ class Executor weak_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_); }; -namespace executor -{ - -using Executor [[deprecated("use rclcpp::Executor instead")]] = rclcpp::Executor; - -} // namespace executor } // namespace rclcpp #endif // RCLCPP__EXECUTOR_HPP_ diff --git a/rclcpp/include/rclcpp/executor_options.hpp b/rclcpp/include/rclcpp/executor_options.hpp index d5ec6d0da9..066f29eb4e 100644 --- a/rclcpp/include/rclcpp/executor_options.hpp +++ b/rclcpp/include/rclcpp/executor_options.hpp @@ -38,20 +38,6 @@ struct ExecutorOptions size_t max_conditions; }; -namespace executor -{ - -using ExecutorArgs [[deprecated("use rclcpp::ExecutorOptions instead")]] = ExecutorOptions; - -[[deprecated("use rclcpp::ExecutorOptions() instead")]] -inline -rclcpp::ExecutorOptions -create_default_executor_arguments() -{ - return rclcpp::ExecutorOptions(); -} - -} // namespace executor } // namespace rclcpp #endif // RCLCPP__EXECUTOR_OPTIONS_HPP_ diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index d36a18d4dc..079be09b28 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -349,15 +349,6 @@ class Service : public ServiceBase send_response(*request_header, *response); } - [[deprecated("use the send_response() which takes references instead of shared pointers")]] - void - send_response( - std::shared_ptr req_id, - std::shared_ptr response) - { - send_response(*req_id, *response); - } - void send_response(rmw_request_id_t & req_id, typename ServiceT::Response & response) { diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index 2b6a3db37f..5011a12c6a 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -143,21 +143,6 @@ RCLCPP_PUBLIC bool ok(rclcpp::Context::SharedPtr context = nullptr); -/// Return true if init() has already been called for the given context. -/** - * If nullptr is given for the context, then the global context is used, i.e. - * the context initialized by rclcpp::init(). - * - * Deprecated, as it is no longer different from rcl_ok(). - * - * \param[in] context Optional check for initialization of this Context. - * \return true if the context is initialized, and false otherwise - */ -[[deprecated("use the function ok() instead, which has the same usage.")]] -RCLCPP_PUBLIC -bool -is_initialized(rclcpp::Context::SharedPtr context = nullptr); - /// Shutdown rclcpp context, invalidating it for derived entities. /** * If nullptr is given for the context, then the global context is used, i.e. diff --git a/rclcpp/test/rclcpp/CMakeLists.txt b/rclcpp/test/rclcpp/CMakeLists.txt index f6244b5815..010a911889 100644 --- a/rclcpp/test/rclcpp/CMakeLists.txt +++ b/rclcpp/test/rclcpp/CMakeLists.txt @@ -558,14 +558,6 @@ if(TARGET test_utilities) target_link_libraries(test_utilities ${PROJECT_NAME} mimick) endif() -ament_add_gtest(test_init test_init.cpp - APPEND_LIBRARY_DIRS "${append_library_dirs}") -if(TARGET test_init) - ament_target_dependencies(test_init - "rcl") - target_link_libraries(test_init ${PROJECT_NAME}) -endif() - ament_add_gtest(test_interface_traits test_interface_traits.cpp APPEND_LIBRARY_DIRS "${append_library_dirs}") if(TARGET test_interface_traits) diff --git a/rclcpp/test/rclcpp/test_init.cpp b/rclcpp/test/rclcpp/test_init.cpp deleted file mode 100644 index bee35f3992..0000000000 --- a/rclcpp/test/rclcpp/test_init.cpp +++ /dev/null @@ -1,66 +0,0 @@ -// Copyright 2018 Open Source Robotics Foundation, Inc. -// -// 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 - -#include "rclcpp/exceptions.hpp" -#include "rclcpp/utilities.hpp" - -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - -TEST(TestInit, is_initialized) { - EXPECT_FALSE(rclcpp::is_initialized()); - - rclcpp::init(0, nullptr); - - EXPECT_TRUE(rclcpp::is_initialized()); - - rclcpp::shutdown(); - - EXPECT_FALSE(rclcpp::is_initialized()); -} - -TEST(TestInit, initialize_with_ros_args) { - EXPECT_FALSE(rclcpp::is_initialized()); - - rclcpp::init(0, nullptr); - - EXPECT_TRUE(rclcpp::is_initialized()); - - rclcpp::shutdown(); - - EXPECT_FALSE(rclcpp::is_initialized()); -} - -TEST(TestInit, initialize_with_unknown_ros_args) { - EXPECT_FALSE(rclcpp::is_initialized()); - - const char * const argv[] = {"--ros-args", "unknown"}; - const int argc = static_cast(sizeof(argv) / sizeof(const char *)); - EXPECT_THROW({rclcpp::init(argc, argv);}, rclcpp::exceptions::UnknownROSArgsError); - - EXPECT_FALSE(rclcpp::is_initialized()); -} - -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif