Skip to content

Commit 4f50775

Browse files
authored
Removed deprecated rcpputils Path (#2834)
Signed-off-by: Alejandro Hernandez Cordero <[email protected]>
1 parent 7bd14d8 commit 4f50775

File tree

2 files changed

+0
-56
lines changed

2 files changed

+0
-56
lines changed

rclcpp/include/rclcpp/logger.hpp

Lines changed: 0 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -78,34 +78,6 @@ RCLCPP_PUBLIC
7878
Logger
7979
get_node_logger(const rcl_node_t * node);
8080

81-
// TODO(ahcorde): Remove deprecated class on the next release (in Rolling after Kilted).
82-
#if !defined(_WIN32)
83-
# pragma GCC diagnostic push
84-
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
85-
#else // !defined(_WIN32)
86-
# pragma warning(push)
87-
# pragma warning(disable: 4996)
88-
#endif
89-
/// Get the current logging directory.
90-
/**
91-
* For more details of how the logging directory is determined,
92-
* see rcl_logging_get_logging_directory().
93-
*
94-
* \returns the logging directory being used.
95-
* \throws rclcpp::exceptions::RCLError if an unexpected error occurs.
96-
*/
97-
[[deprecated("use rclcpp::get_log_directory instead of rclcpp::get_logging_directory")]]
98-
RCLCPP_PUBLIC
99-
rcpputils::fs::path
100-
get_logging_directory();
101-
102-
// remove warning suppression
103-
#if !defined(_WIN32)
104-
# pragma GCC diagnostic pop
105-
#else // !defined(_WIN32)
106-
# pragma warning(pop)
107-
#endif
108-
10981
/// Get the current logging directory.
11082
/**
11183
* For more details of how the logging directory is determined,

rclcpp/src/rclcpp/logger.cpp

Lines changed: 0 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -55,34 +55,6 @@ get_node_logger(const rcl_node_t * node)
5555
return rclcpp::get_logger(logger_name);
5656
}
5757

58-
// TODO(ahcorde): Remove deprecated class on the next release (in Rolling after Kilted).
59-
#if !defined(_WIN32)
60-
# pragma GCC diagnostic push
61-
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
62-
#else // !defined(_WIN32)
63-
# pragma warning(push)
64-
# pragma warning(disable: 4996)
65-
#endif
66-
rcpputils::fs::path
67-
get_logging_directory()
68-
{
69-
char * log_dir = NULL;
70-
auto allocator = rcutils_get_default_allocator();
71-
rcl_logging_ret_t ret = rcl_logging_get_logging_directory(allocator, &log_dir);
72-
if (RCL_LOGGING_RET_OK != ret) {
73-
rclcpp::exceptions::throw_from_rcl_error(ret);
74-
}
75-
std::string path{log_dir};
76-
allocator.deallocate(log_dir, allocator.state);
77-
return path;
78-
}
79-
// remove warning suppression
80-
#if !defined(_WIN32)
81-
# pragma GCC diagnostic pop
82-
#else // !defined(_WIN32)
83-
# pragma warning(pop)
84-
#endif
85-
8658
std::filesystem::path
8759
get_log_directory()
8860
{

0 commit comments

Comments
 (0)