Skip to content

Commit

Permalink
remove deprecated code which was deprecated in foxy and should be rem…
Browse files Browse the repository at this point in the history
…oved in galactic (#1622)

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored Apr 6, 2021
1 parent 091a8bc commit 61fcc76
Show file tree
Hide file tree
Showing 9 changed files with 0 additions and 147 deletions.
6 changes: 0 additions & 6 deletions rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,6 @@ struct AnyExecutable
std::shared_ptr<void> data;
};

namespace executor
{

using AnyExecutable [[deprecated("use rclcpp::AnyExecutable instead")]] = AnyExecutable;

} // namespace executor
} // namespace rclcpp

#endif // RCLCPP__ANY_EXECUTABLE_HPP_
7 changes: 0 additions & 7 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_
16 changes: 0 additions & 16 deletions rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
6 changes: 0 additions & 6 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_
14 changes: 0 additions & 14 deletions rclcpp/include/rclcpp/executor_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_
9 changes: 0 additions & 9 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rmw_request_id_t> req_id,
std::shared_ptr<typename ServiceT::Response> response)
{
send_response(*req_id, *response);
}

void
send_response(rmw_request_id_t & req_id, typename ServiceT::Response & response)
{
Expand Down
15 changes: 0 additions & 15 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
8 changes: 0 additions & 8 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
66 changes: 0 additions & 66 deletions rclcpp/test/rclcpp/test_init.cpp

This file was deleted.

0 comments on commit 61fcc76

Please sign in to comment.